OrbbecSDK 2.6.3
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
171 ob_error *error = nullptr;
172 ob_config_enable_lidar_stream(impl_, scanRate, format, &error);
173 Error::handle(&error);
174 }
175
181 ob_error *error = nullptr;
182 ob_config_enable_all_stream(impl_, &error);
183 Error::handle(&error);
184 }
185
191 void disableStream(OBStreamType streamType) const {
192 ob_error *error = nullptr;
193 ob_config_disable_stream(impl_, streamType, &error);
194 Error::handle(&error);
195 }
196
203 void disableStream(OBSensorType sensorType) const {
204 auto streamType = ob::TypeHelper::convertSensorTypeToStreamType(sensorType);
205 disableStream(streamType);
206 }
207
211 void disableAllStream() const {
212 ob_error *error = nullptr;
213 ob_config_disable_all_stream(impl_, &error);
214 Error::handle(&error);
215 }
216
222 std::shared_ptr<StreamProfileList> getEnabledStreamProfileList() const {
223 ob_error *error = nullptr;
224 auto list = ob_config_get_enabled_stream_profile_list(impl_, &error);
225 Error::handle(&error);
226 return std::make_shared<StreamProfileList>(list);
227 }
228
234 void setAlignMode(OBAlignMode mode) const {
235 ob_error *error = nullptr;
236 ob_config_set_align_mode(impl_, mode, &error);
237 Error::handle(&error);
238 }
239
245 void setDepthScaleRequire(bool enable) const {
246 ob_error *error = nullptr;
248 Error::handle(&error);
249 }
250
259 ob_error *error = nullptr;
261 Error::handle(&error);
262 }
263};
264
265class Pipeline {
266public:
272 typedef std::function<void(std::shared_ptr<FrameSet> frame)> FrameSetCallback;
273
274private:
275 ob_pipeline_t *impl_;
276 FrameSetCallback callback_;
277
278public:
285 ob_error *error = nullptr;
286 impl_ = ob_create_pipeline(&error);
287 Error::handle(&error);
288 }
289
295 explicit Pipeline(std::shared_ptr<Device> device) {
296 ob_error *error = nullptr;
297 impl_ = ob_create_pipeline_with_device(device->getImpl(), &error);
298 Error::handle(&error);
299 }
300
304 ~Pipeline() noexcept {
305 ob_error *error = nullptr;
306 ob_delete_pipeline(impl_, &error);
307 Error::handle(&error, false);
308 }
309
315 void start(std::shared_ptr<Config> config = nullptr) const {
316 ob_error *error = nullptr;
317 ob_config_t *config_impl = config == nullptr ? nullptr : config->getImpl();
318 ob_pipeline_start_with_config(impl_, config_impl, &error);
319 Error::handle(&error);
320 }
321
328 void start(std::shared_ptr<Config> config, FrameSetCallback callback) {
329 callback_ = callback;
330 ob_error *error = nullptr;
331 ob_pipeline_start_with_callback(impl_, config ? config->getImpl() : nullptr, &Pipeline::frameSetCallback, this, &error);
332 Error::handle(&error);
333 }
334
335 static void frameSetCallback(ob_frame_t *frameSet, void *userData) {
336 auto pipeline = static_cast<Pipeline *>(userData);
337 pipeline->callback_(std::make_shared<FrameSet>(frameSet));
338 }
339
343 void stop() const {
344 ob_error *error = nullptr;
345 ob_pipeline_stop(impl_, &error);
346 Error::handle(&error);
347 }
348
355 std::shared_ptr<Config> getConfig() const {
356 ob_error *error = nullptr;
357 auto config = ob_pipeline_get_config(impl_, &error);
358 Error::handle(&error);
359 return std::make_shared<Config>(config);
360 }
361
369 std::shared_ptr<FrameSet> waitForFrameset(uint32_t timeoutMs = 1000) const {
370 ob_error *error = nullptr;
371 auto frameSet = ob_pipeline_wait_for_frameset(impl_, timeoutMs, &error);
372 if(frameSet == nullptr) {
373 return nullptr;
374 }
375 Error::handle(&error);
376 return std::make_shared<FrameSet>(frameSet);
377 }
378
384 std::shared_ptr<Device> getDevice() const {
385 ob_error *error = nullptr;
386 auto device = ob_pipeline_get_device(impl_, &error);
387 Error::handle(&error);
388 return std::make_shared<Device>(device);
389 }
390
398 std::shared_ptr<StreamProfileList> getStreamProfileList(OBSensorType sensorType) const {
399 ob_error *error = nullptr;
400 auto list = ob_pipeline_get_stream_profile_list(impl_, sensorType, &error);
401 Error::handle(&error);
402 return std::make_shared<StreamProfileList>(list);
403 }
404
415 std::shared_ptr<StreamProfileList> getD2CDepthProfileList(std::shared_ptr<StreamProfile> colorProfile, OBAlignMode alignMode) {
416 ob_error *error = nullptr;
417 auto list = ob_get_d2c_depth_profile_list(impl_, colorProfile->getImpl(), alignMode, &error);
418 Error::handle(&error);
419 return std::make_shared<StreamProfileList>(list);
420 }
421
425 void enableFrameSync() const {
426 ob_error *error = nullptr;
427 ob_pipeline_enable_frame_sync(impl_, &error);
428 Error::handle(&error);
429 }
430
434 void disableFrameSync() const {
435 ob_error *error = nullptr;
436 ob_pipeline_disable_frame_sync(impl_, &error);
437 Error::handle(&error);
438 }
439
440public:
441 // The following interfaces are deprecated and are retained here for compatibility purposes.
442
444 ob_error *error = nullptr;
445 OBCameraParam cameraParam = ob_pipeline_get_camera_param(impl_, &error);
446 Error::handle(&error);
447 return cameraParam;
448 }
449
450 OBCameraParam getCameraParamWithProfile(uint32_t colorWidth, uint32_t colorHeight, uint32_t depthWidth, uint32_t depthHeight) {
451 ob_error *error = nullptr;
452 OBCameraParam cameraParam = ob_pipeline_get_camera_param_with_profile(impl_, colorWidth, colorHeight, depthWidth, depthHeight, &error);
453 Error::handle(&error);
454 return cameraParam;
455 }
456
457 OBCalibrationParam getCalibrationParam(std::shared_ptr<Config> config) {
458 ob_error *error = nullptr;
459 OBCalibrationParam calibrationParam = ob_pipeline_get_calibration_param(impl_, config->getImpl(), &error);
460 Error::handle(&error);
461 return calibrationParam;
462 }
463
464 std::shared_ptr<FrameSet> waitForFrames(uint32_t timeoutMs = 1000) const {
465 return waitForFrameset(timeoutMs);
466 }
467};
468
469} // 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
OBLiDARScanRate
Data structures for LiDAR scan rate.
Definition ObTypes.h:659
OBSensorType
Enumeration value describing the sensor type.
Definition ObTypes.h:130
OBGyroFullScaleRange
Enumeration of gyroscope ranges.
Definition ObTypes.h:616
#define OB_ACCEL_SAMPLE_RATE_ANY
Definition ObTypes.h:51
OBFormat
Enumeration value describing the pixel format.
Definition ObTypes.h:204
#define OB_GYRO_FULL_SCALE_RANGE_ANY
Definition ObTypes.h:52
OBStreamType
Enumeration value describing the type of data stream.
Definition ObTypes.h:149
enum OBIMUSampleRate OBGyroSampleRate
#define OB_GYRO_SAMPLE_RATE_ANY
Definition ObTypes.h:53
OBAccelFullScaleRange
Enumeration of accelerometer ranges.
Definition ObTypes.h:634
#define OB_LIDAR_SCAN_ANY
Definition ObTypes.h:54
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:518
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_enable_lidar_stream(ob_config *config, ob_lidar_scan_rate scan_rate, ob_format format, ob_error **error)
Enable LiDAR stream with specified parameters.
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:245
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:191
~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:211
std::shared_ptr< StreamProfileList > getEnabledStreamProfileList() const
Get the Enabled Stream Profile List.
Definition Pipeline.hpp:222
void disableStream(OBSensorType sensorType) const
Disable a sensor stream to be used in the pipeline.
Definition Pipeline.hpp:203
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:234
void enableLiDARStream(OBLiDARScanRate scanRate=OB_LIDAR_SCAN_ANY, OBFormat format=OB_FORMAT_ANY) const
Enable a LiDAR stream to be used in the pipeline.
Definition Pipeline.hpp:170
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:180
void setFrameAggregateOutputMode(OBFrameAggregateOutputMode mode) const
Set the frame aggregation output mode for the pipeline configuration.
Definition Pipeline.hpp:258
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:457
std::shared_ptr< Config > getConfig() const
Get the pipeline configuration parameters.
Definition Pipeline.hpp:355
void enableFrameSync() const
Turn on frame synchronization.
Definition Pipeline.hpp:425
~Pipeline() noexcept
Destroy the pipeline object.
Definition Pipeline.hpp:304
Pipeline()
Pipeline is a high-level interface for applications, algorithms related RGBD data streams....
Definition Pipeline.hpp:284
std::shared_ptr< StreamProfileList > getStreamProfileList(OBSensorType sensorType) const
Get the stream profile of the specified sensor.
Definition Pipeline.hpp:398
void start(std::shared_ptr< Config > config, FrameSetCallback callback)
Start the pipeline and set the frameset data callback.
Definition Pipeline.hpp:328
OBCameraParam getCameraParamWithProfile(uint32_t colorWidth, uint32_t colorHeight, uint32_t depthWidth, uint32_t depthHeight)
Definition Pipeline.hpp:450
void start(std::shared_ptr< Config > config=nullptr) const
Start the pipeline with configuration parameters.
Definition Pipeline.hpp:315
void stop() const
Stop the pipeline.
Definition Pipeline.hpp:343
static void frameSetCallback(ob_frame_t *frameSet, void *userData)
Definition Pipeline.hpp:335
std::shared_ptr< FrameSet > waitForFrames(uint32_t timeoutMs=1000) const
Definition Pipeline.hpp:464
Pipeline(std::shared_ptr< Device > device)
Pipeline(std::shared_ptr< Device > device ) Function for multi-device operations. Multiple devices ne...
Definition Pipeline.hpp:295
std::shared_ptr< FrameSet > waitForFrameset(uint32_t timeoutMs=1000) const
Wait for frameset.
Definition Pipeline.hpp:369
std::function< void(std::shared_ptr< FrameSet > frame)> FrameSetCallback
FrameSetCallback is a callback function type for frameset data arrival.
Definition Pipeline.hpp:272
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:415
OBCameraParam getCameraParam()
Definition Pipeline.hpp:443
void disableFrameSync() const
Turn off frame synchronization.
Definition Pipeline.hpp:434
std::shared_ptr< Device > getDevice() const
Get the device object.
Definition Pipeline.hpp:384
static OBStreamType convertSensorTypeToStreamType(OBSensorType type)
Convert OBSensorType to OBStreamType type and then return.
Definition Context.hpp:22
calibration parameters
Definition ObTypes.h:479
Structure for camera parameters.
Definition ObTypes.h:460
The error class exposed by the SDK, users can get detailed error information according to the error.
Definition ObTypes.h:119