OrbbecSDK 2.5.5
OrbbecSDK: Software-Development-Kit for Orbbec 3D Cameras
Loading...
Searching...
No Matches
Pipeline.hpp
Go to the documentation of this file.
1// Copyright (c) Orbbec Inc. All Rights Reserved.
2// Licensed under the MIT License.
3
9#pragma once
10
11#include "Frame.hpp"
12#include "Device.hpp"
13#include "StreamProfile.hpp"
14
18
19#include <memory>
20#include <functional>
21namespace ob {
22
28class Config {
29private:
30 ob_config_t *impl_;
31
32public:
37 ob_error *error = nullptr;
38 impl_ = ob_create_config(&error);
39 Error::handle(&error);
40 }
41
42 explicit Config(ob_config_t *impl) : impl_(impl) {}
43
47 ~Config() noexcept {
48 ob_error *error = nullptr;
49 ob_delete_config(impl_, &error);
50 Error::handle(&error, false);
51 }
52
53 ob_config_t *getImpl() const {
54 return impl_;
55 }
56
62 void enableStream(OBStreamType streamType) const {
63 ob_error *error = nullptr;
64 ob_config_enable_stream(impl_, streamType, &error);
65 Error::handle(&error);
66 }
67
74 void enableStream(OBSensorType sensorType) const {
75 auto streamType = ob::TypeHelper::convertSensorTypeToStreamType(sensorType);
76 enableStream(streamType);
77 }
78
84 void enableStream(std::shared_ptr<const StreamProfile> streamProfile) const {
85 ob_error *error = nullptr;
86 auto c_stream_profile = streamProfile->getImpl();
87 ob_config_enable_stream_with_stream_profile(impl_, c_stream_profile, &error);
88 Error::handle(&error);
89 }
90
104 void enableVideoStream(OBStreamType streamType, uint32_t width = OB_WIDTH_ANY, uint32_t height = OB_HEIGHT_ANY, uint32_t fps = OB_FPS_ANY,
105 OBFormat format = OB_FORMAT_ANY) const {
106 ob_error *error = nullptr;
107 ob_config_enable_video_stream(impl_, streamType, width, height, fps, format, &error);
108 Error::handle(&error);
109 }
110
121 void enableVideoStream(OBSensorType sensorType, uint32_t width = OB_WIDTH_ANY, uint32_t height = OB_HEIGHT_ANY, uint32_t fps = OB_FPS_ANY,
122 OBFormat format = OB_FORMAT_ANY) const {
123 auto streamType = ob::TypeHelper::convertSensorTypeToStreamType(sensorType);
124 enableVideoStream(streamType, width, height, fps, format);
125 }
126
138 OBAccelSampleRate sampleRate = OB_ACCEL_SAMPLE_RATE_ANY) const {
139 ob_error *error = nullptr;
140 ob_config_enable_accel_stream(impl_, fullScaleRange, sampleRate, &error);
141 Error::handle(&error);
142 }
143
155 ob_error *error = nullptr;
156 ob_config_enable_gyro_stream(impl_, fullScaleRange, sampleRate, &error);
157 Error::handle(&error);
158 }
159
165 ob_error *error = nullptr;
166 ob_config_enable_all_stream(impl_, &error);
167 Error::handle(&error);
168 }
169
175 void disableStream(OBStreamType streamType) const {
176 ob_error *error = nullptr;
177 ob_config_disable_stream(impl_, streamType, &error);
178 Error::handle(&error);
179 }
180
187 void disableStream(OBSensorType sensorType) const {
188 auto streamType = ob::TypeHelper::convertSensorTypeToStreamType(sensorType);
189 disableStream(streamType);
190 }
191
195 void disableAllStream() const {
196 ob_error *error = nullptr;
197 ob_config_disable_all_stream(impl_, &error);
198 Error::handle(&error);
199 }
200
206 std::shared_ptr<StreamProfileList> getEnabledStreamProfileList() const {
207 ob_error *error = nullptr;
208 auto list = ob_config_get_enabled_stream_profile_list(impl_, &error);
209 Error::handle(&error);
210 return std::make_shared<StreamProfileList>(list);
211 }
212
218 void setAlignMode(OBAlignMode mode) const {
219 ob_error *error = nullptr;
220 ob_config_set_align_mode(impl_, mode, &error);
221 Error::handle(&error);
222 }
223
229 void setDepthScaleRequire(bool enable) const {
230 ob_error *error = nullptr;
232 Error::handle(&error);
233 }
234
243 ob_error *error = nullptr;
245 Error::handle(&error);
246 }
247};
248
249class Pipeline {
250public:
256 typedef std::function<void(std::shared_ptr<FrameSet> frame)> FrameSetCallback;
257
258private:
259 ob_pipeline_t *impl_;
260 FrameSetCallback callback_;
261
262public:
269 ob_error *error = nullptr;
270 impl_ = ob_create_pipeline(&error);
271 Error::handle(&error);
272 }
273
279 explicit Pipeline(std::shared_ptr<Device> device) {
280 ob_error *error = nullptr;
281 impl_ = ob_create_pipeline_with_device(device->getImpl(), &error);
282 Error::handle(&error);
283 }
284
288 ~Pipeline() noexcept {
289 ob_error *error = nullptr;
290 ob_delete_pipeline(impl_, &error);
291 Error::handle(&error, false);
292 }
293
299 void start(std::shared_ptr<Config> config = nullptr) const {
300 ob_error *error = nullptr;
301 ob_config_t *config_impl = config == nullptr ? nullptr : config->getImpl();
302 ob_pipeline_start_with_config(impl_, config_impl, &error);
303 Error::handle(&error);
304 }
305
312 void start(std::shared_ptr<Config> config, FrameSetCallback callback) {
313 callback_ = callback;
314 ob_error *error = nullptr;
315 ob_pipeline_start_with_callback(impl_, config ? config->getImpl() : nullptr, &Pipeline::frameSetCallback, this, &error);
316 Error::handle(&error);
317 }
318
319 static void frameSetCallback(ob_frame_t *frameSet, void *userData) {
320 auto pipeline = static_cast<Pipeline *>(userData);
321 pipeline->callback_(std::make_shared<FrameSet>(frameSet));
322 }
323
327 void stop() const {
328 ob_error *error = nullptr;
329 ob_pipeline_stop(impl_, &error);
330 Error::handle(&error);
331 }
332
339 std::shared_ptr<Config> getConfig() const {
340 ob_error *error = nullptr;
341 auto config = ob_pipeline_get_config(impl_, &error);
342 Error::handle(&error);
343 return std::make_shared<Config>(config);
344 }
345
352 std::shared_ptr<FrameSet> waitForFrameset(uint32_t timeoutMs = 1000) const {
353 ob_error *error = nullptr;
354 auto frameSet = ob_pipeline_wait_for_frameset(impl_, timeoutMs, &error);
355 if(frameSet == nullptr) {
356 return nullptr;
357 }
358 Error::handle(&error);
359 return std::make_shared<FrameSet>(frameSet);
360 }
361
367 std::shared_ptr<Device> getDevice() const {
368 ob_error *error = nullptr;
369 auto device = ob_pipeline_get_device(impl_, &error);
370 Error::handle(&error);
371 return std::make_shared<Device>(device);
372 }
373
380 std::shared_ptr<StreamProfileList> getStreamProfileList(OBSensorType sensorType) const {
381 ob_error *error = nullptr;
382 auto list = ob_pipeline_get_stream_profile_list(impl_, sensorType, &error);
383 Error::handle(&error);
384 return std::make_shared<StreamProfileList>(list);
385 }
386
397 std::shared_ptr<StreamProfileList> getD2CDepthProfileList(std::shared_ptr<StreamProfile> colorProfile, OBAlignMode alignMode) {
398 ob_error *error = nullptr;
399 auto list = ob_get_d2c_depth_profile_list(impl_, colorProfile->getImpl(), alignMode, &error);
400 Error::handle(&error);
401 return std::make_shared<StreamProfileList>(list);
402 }
403
407 void enableFrameSync() const {
408 ob_error *error = nullptr;
409 ob_pipeline_enable_frame_sync(impl_, &error);
410 Error::handle(&error);
411 }
412
416 void disableFrameSync() const {
417 ob_error *error = nullptr;
418 ob_pipeline_disable_frame_sync(impl_, &error);
419 Error::handle(&error);
420 }
421
422public:
423 // The following interfaces are deprecated and are retained here for compatibility purposes.
424
426 ob_error *error = nullptr;
427 OBCameraParam cameraParam = ob_pipeline_get_camera_param(impl_, &error);
428 Error::handle(&error);
429 return cameraParam;
430 }
431
432 OBCameraParam getCameraParamWithProfile(uint32_t colorWidth, uint32_t colorHeight, uint32_t depthWidth, uint32_t depthHeight) {
433 ob_error *error = nullptr;
434 OBCameraParam cameraParam = ob_pipeline_get_camera_param_with_profile(impl_, colorWidth, colorHeight, depthWidth, depthHeight, &error);
435 Error::handle(&error);
436 return cameraParam;
437 }
438
439 OBCalibrationParam getCalibrationParam(std::shared_ptr<Config> config) {
440 ob_error *error = nullptr;
441 OBCalibrationParam calibrationParam = ob_pipeline_get_calibration_param(impl_, config->getImpl(), &error);
442 Error::handle(&error);
443 return calibrationParam;
444 }
445
446 std::shared_ptr<FrameSet> waitForFrames(uint32_t timeoutMs = 1000) const {
447 return waitForFrameset(timeoutMs);
448 }
449};
450
451} // namespace ob
Device related types, including operations such as getting and creating a device, setting and obtaini...
Frame related type, which is mainly used to obtain frame data and frame information.
#define OB_ACCEL_FULL_SCALE_RANGE_ANY
Definition ObTypes.h:50
OBSensorType
Enumeration value describing the sensor type.
Definition ObTypes.h:128
OBGyroFullScaleRange
Enumeration of gyroscope ranges.
Definition ObTypes.h:604
#define OB_ACCEL_SAMPLE_RATE_ANY
Definition ObTypes.h:51
OBFormat
Enumeration value describing the pixel format.
Definition ObTypes.h:199
#define OB_GYRO_FULL_SCALE_RANGE_ANY
Definition ObTypes.h:52
OBStreamType
Enumeration value describing the type of data stream.
Definition ObTypes.h:146
enum OBIMUSampleRate OBGyroSampleRate
#define OB_GYRO_SAMPLE_RATE_ANY
Definition ObTypes.h:53
OBAccelFullScaleRange
Enumeration of accelerometer ranges.
Definition ObTypes.h:622
enum OBIMUSampleRate OBAccelSampleRate
#define OB_WIDTH_ANY
Definition ObTypes.h:44
enum OB_FRAME_AGGREGATE_OUTPUT_MODE OBFrameAggregateOutputMode
#define OB_FPS_ANY
Definition ObTypes.h:46
#define OB_HEIGHT_ANY
Definition ObTypes.h:45
#define OB_FORMAT_ANY
Definition ObTypes.h:47
OBAlignMode
Alignment mode.
Definition ObTypes.h:506
The SDK's advanced API can quickly implement functions such as switching streaming,...
OB_EXPORT ob_pipeline * ob_create_pipeline_with_device(const ob_device *dev, ob_error **error)
Using device objects to create pipeline objects.
OB_EXPORT ob_pipeline * ob_create_pipeline(ob_error **error)
Create a pipeline object.
OB_EXPORT void ob_pipeline_enable_frame_sync(ob_pipeline *pipeline, ob_error **error)
Enable frame synchronization.
OB_EXPORT void ob_config_set_frame_aggregate_output_mode(ob_config *config, ob_frame_aggregate_output_mode mode, ob_error **error)
Set the frame aggregation output mode for the pipeline configuration.
OB_EXPORT void ob_config_enable_stream(ob_config *config, ob_stream_type stream_type, ob_error **error)
Enable a stream with default profile.
OB_EXPORT ob_camera_param ob_pipeline_get_camera_param_with_profile(ob_pipeline *pipeline, uint32_t colorWidth, uint32_t colorHeight, uint32_t depthWidth, uint32_t depthHeight, ob_error **error)
Get the current camera parameters.
OB_EXPORT void ob_delete_config(ob_config *config, ob_error **error)
Delete the pipeline configuration.
OB_EXPORT void ob_config_enable_video_stream(ob_config *config, ob_stream_type stream_type, uint32_t width, uint32_t height, uint32_t fps, ob_format format, ob_error **error)
Enable video stream with specified parameters.
OB_EXPORT ob_config * ob_create_config(ob_error **error)
Create the pipeline configuration.
OB_EXPORT void ob_config_disable_stream(ob_config *config, ob_stream_type type, ob_error **error)
Disable a specific stream in the pipeline configuration.
OB_EXPORT void ob_delete_pipeline(ob_pipeline *pipeline, ob_error **error)
Delete pipeline objects.
OB_EXPORT ob_device * ob_pipeline_get_device(const ob_pipeline *pipeline, ob_error **error)
Get the device object associated with the pipeline.
OB_EXPORT ob_stream_profile_list * ob_get_d2c_depth_profile_list(const ob_pipeline *pipeline, const ob_stream_profile *color_profile, ob_align_mode align_mode, ob_error **error)
Return a list of D2C-enabled depth sensor resolutions corresponding to the input color sensor resolut...
OB_EXPORT void ob_config_set_align_mode(ob_config *config, ob_align_mode mode, ob_error **error)
Set the alignment mode for the pipeline configuration.
OB_EXPORT ob_frame * ob_pipeline_wait_for_frameset(ob_pipeline *pipeline, uint32_t timeout_ms, ob_error **error)
Wait for a set of frames to be returned synchronously.
OB_EXPORT ob_stream_profile_list * ob_pipeline_get_stream_profile_list(const ob_pipeline *pipeline, ob_sensor_type sensorType, ob_error **error)
Get the stream profile list associated with the pipeline.
OB_EXPORT ob_config * ob_pipeline_get_config(const ob_pipeline *pipeline, ob_error **error)
Get the configuration object associated with the pipeline.
OB_EXPORT void ob_config_enable_accel_stream(ob_config *config, ob_accel_full_scale_range full_scale_range, ob_accel_sample_rate sample_rate, ob_error **error)
Enable accelerometer stream with specified parameters.
OB_EXPORT void ob_pipeline_stop(ob_pipeline *pipeline, ob_error **error)
Stop pipeline.
OB_EXPORT void ob_config_enable_all_stream(ob_config *config, ob_error **error)
Enable all streams in the pipeline configuration.
OB_EXPORT void ob_config_enable_stream_with_stream_profile(ob_config *config, const ob_stream_profile *profile, ob_error **error)
Enable a stream according to the stream profile.
OB_EXPORT void ob_pipeline_start_with_callback(ob_pipeline *pipeline, const ob_config *config, ob_frameset_callback callback, void *user_data, ob_error **error)
Start the pipeline and set the frame collection data callback.
OB_EXPORT void ob_config_disable_all_stream(ob_config *config, ob_error **error)
Disable all streams in the pipeline configuration.
OB_EXPORT ob_stream_profile_list * ob_config_get_enabled_stream_profile_list(const ob_config *config, ob_error **error)
Get the enabled stream profile list in the pipeline configuration.
OB_EXPORT void ob_config_set_depth_scale_after_align_require(ob_config *config, bool enable, ob_error **error)
Set whether depth scaling is required after enable depth to color alignment.
OB_EXPORT void ob_pipeline_disable_frame_sync(ob_pipeline *pipeline, ob_error **error)
Disable frame synchronization.
OB_EXPORT ob_camera_param ob_pipeline_get_camera_param(ob_pipeline *pipeline, ob_error **error)
Get current camera parameters.
OB_EXPORT void ob_pipeline_start_with_config(ob_pipeline *pipeline, const ob_config *config, ob_error **error)
Start the pipeline with configuration parameters.
OB_EXPORT void ob_config_enable_gyro_stream(ob_config *config, ob_gyro_full_scale_range full_scale_range, ob_gyro_sample_rate sample_rate, ob_error **error)
Enable gyroscope stream with specified parameters.
OB_EXPORT ob_calibration_param ob_pipeline_get_calibration_param(ob_pipeline *pipeline, ob_config *config, ob_error **error)
Get device calibration parameters with the specified configuration.
The stream profile related type is used to get information such as the width, height,...
void setDepthScaleRequire(bool enable) const
Set whether the depth needs to be scaled after setting D2C.
Definition Pipeline.hpp:229
ob_config_t * getImpl() const
Definition Pipeline.hpp:53
void disableStream(OBStreamType streamType) const
Disable a stream to be used in the pipeline.
Definition Pipeline.hpp:175
~Config() noexcept
Destroy the Config object.
Definition Pipeline.hpp:47
void enableStream(OBSensorType sensorType) const
Enable a stream with a specific sensor type.
Definition Pipeline.hpp:74
void enableVideoStream(OBSensorType sensorType, uint32_t width=OB_WIDTH_ANY, uint32_t height=OB_HEIGHT_ANY, uint32_t fps=OB_FPS_ANY, OBFormat format=OB_FORMAT_ANY) const
Enable a video stream to be used in the pipeline.
Definition Pipeline.hpp:121
void disableAllStream() const
Disable all streams to be used in the pipeline.
Definition Pipeline.hpp:195
std::shared_ptr< StreamProfileList > getEnabledStreamProfileList() const
Get the Enabled Stream Profile List.
Definition Pipeline.hpp:206
void disableStream(OBSensorType sensorType) const
Disable a sensor stream to be used in the pipeline.
Definition Pipeline.hpp:187
void enableStream(OBStreamType streamType) const
enable a stream with a specific stream type
Definition Pipeline.hpp:62
void setAlignMode(OBAlignMode mode) const
Set the alignment mode.
Definition Pipeline.hpp:218
Config(ob_config_t *impl)
Definition Pipeline.hpp:42
Config()
Construct a new Config object.
Definition Pipeline.hpp:36
void enableStream(std::shared_ptr< const StreamProfile > streamProfile) const
Enable a stream to be used in the pipeline.
Definition Pipeline.hpp:84
void enableGyroStream(OBGyroFullScaleRange fullScaleRange=OB_GYRO_FULL_SCALE_RANGE_ANY, OBGyroSampleRate sampleRate=OB_GYRO_SAMPLE_RATE_ANY) const
Enable a gyroscope stream to be used in the pipeline.
Definition Pipeline.hpp:154
void enableAccelStream(OBAccelFullScaleRange fullScaleRange=OB_ACCEL_FULL_SCALE_RANGE_ANY, OBAccelSampleRate sampleRate=OB_ACCEL_SAMPLE_RATE_ANY) const
Enable an accelerometer stream to be used in the pipeline.
Definition Pipeline.hpp:137
void enableVideoStream(OBStreamType streamType, uint32_t width=OB_WIDTH_ANY, uint32_t height=OB_HEIGHT_ANY, uint32_t fps=OB_FPS_ANY, OBFormat format=OB_FORMAT_ANY) const
Enable a video stream to be used in the pipeline.
Definition Pipeline.hpp:104
void enableAllStream()
Enable all streams to be used in the pipeline.
Definition Pipeline.hpp:164
void setFrameAggregateOutputMode(OBFrameAggregateOutputMode mode) const
Set the frame aggregation output mode for the pipeline configuration.
Definition Pipeline.hpp:242
static void handle(ob_error **error, bool throw_exception=true)
A static function to handle the ob_error and throw an exception if needed.
Definition Error.hpp:38
OBCalibrationParam getCalibrationParam(std::shared_ptr< Config > config)
Definition Pipeline.hpp:439
std::shared_ptr< Config > getConfig() const
Get the pipeline configuration parameters.
Definition Pipeline.hpp:339
void enableFrameSync() const
Turn on frame synchronization.
Definition Pipeline.hpp:407
~Pipeline() noexcept
Destroy the pipeline object.
Definition Pipeline.hpp:288
Pipeline()
Pipeline is a high-level interface for applications, algorithms related RGBD data streams....
Definition Pipeline.hpp:268
std::shared_ptr< StreamProfileList > getStreamProfileList(OBSensorType sensorType) const
Get the stream profile of the specified sensor.
Definition Pipeline.hpp:380
void start(std::shared_ptr< Config > config, FrameSetCallback callback)
Start the pipeline and set the frameset data callback.
Definition Pipeline.hpp:312
OBCameraParam getCameraParamWithProfile(uint32_t colorWidth, uint32_t colorHeight, uint32_t depthWidth, uint32_t depthHeight)
Definition Pipeline.hpp:432
void start(std::shared_ptr< Config > config=nullptr) const
Start the pipeline with configuration parameters.
Definition Pipeline.hpp:299
void stop() const
Stop the pipeline.
Definition Pipeline.hpp:327
static void frameSetCallback(ob_frame_t *frameSet, void *userData)
Definition Pipeline.hpp:319
std::shared_ptr< FrameSet > waitForFrames(uint32_t timeoutMs=1000) const
Definition Pipeline.hpp:446
Pipeline(std::shared_ptr< Device > device)
Pipeline(std::shared_ptr< Device > device ) Function for multi-device operations. Multiple devices ne...
Definition Pipeline.hpp:279
std::shared_ptr< FrameSet > waitForFrameset(uint32_t timeoutMs=1000) const
Wait for frameset.
Definition Pipeline.hpp:352
std::function< void(std::shared_ptr< FrameSet > frame)> FrameSetCallback
FrameSetCallback is a callback function type for frameset data arrival.
Definition Pipeline.hpp:256
std::shared_ptr< StreamProfileList > getD2CDepthProfileList(std::shared_ptr< StreamProfile > colorProfile, OBAlignMode alignMode)
Get the stream profile list of supported depth-to-color alignments.
Definition Pipeline.hpp:397
OBCameraParam getCameraParam()
Definition Pipeline.hpp:425
void disableFrameSync() const
Turn off frame synchronization.
Definition Pipeline.hpp:416
std::shared_ptr< Device > getDevice() const
Get the device object.
Definition Pipeline.hpp:367
static OBStreamType convertSensorTypeToStreamType(OBSensorType type)
Convert OBSensorType to OBStreamType type and then return.
Definition Context.hpp:19
calibration parameters
Definition ObTypes.h:467
Structure for camera parameters.
Definition ObTypes.h:448
The error class exposed by the SDK, users can get detailed error information according to the error.
Definition ObTypes.h:117