Skip to content

Commit 9414eb6

Browse files
committed
Update SDK version to v2.4.7
1 parent 794e05b commit 9414eb6

24 files changed

+210
-39
lines changed

orbbec_camera/SDK/include/libobsensor/h/Advanced.h

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -269,6 +269,42 @@ OB_EXPORT const char *ob_device_frame_interleave_list_get_name(ob_device_frame_i
269269
OB_EXPORT bool ob_device_frame_interleave_list_has_frame_interleave(ob_device_frame_interleave_list *frame_interleave_list, const char *frame_interleave_name,
270270
ob_error **error);
271271

272+
/* @brief Get the available preset resolution config list.
273+
*
274+
* @param device The device object.
275+
* @param error Log error messages.
276+
* @return The available frame interleave list.
277+
*
278+
*/
279+
OB_EXPORT ob_preset_resolution_config_list *ob_device_get_available_preset_resolution_config_list(ob_device *device, ob_error **error);
280+
281+
/* @brief Get the number of preset resolution in the preset resolution list.
282+
*
283+
* @param ob_preset_resolution_config_list The available preset resolution list.
284+
* @param error Log error messages.
285+
* @return The number of preset resolution in the preset resolution list.
286+
*/
287+
OB_EXPORT uint32_t ob_device_preset_resolution_config_get_count(ob_preset_resolution_config_list *ob_preset_resolution_config_list, ob_error **error);
288+
289+
/**
290+
* @brief Get the preset resolution in the preset resolution list.
291+
*
292+
* @param ob_preset_resolution_config_list The available preset resolution list.
293+
* @param index The index of preset resolution in the preset resolution list.
294+
* @param error Log error messages.
295+
* @return The preset resolution in the preset resolution list.
296+
*/
297+
OB_EXPORT OBPresetResolutionConfig ob_device_preset_resolution_config_list_get_item(const ob_preset_resolution_config_list *ob_preset_resolution_config_lis,
298+
uint32_t index, ob_error **error);
299+
300+
/**
301+
* @brief Delete the available preset resolution list.
302+
*
303+
* @param frame_interleave_list The available preset resolution list.
304+
* @param error Log error messages.
305+
*/
306+
OB_EXPORT void ob_delete_preset_resolution_config_list(ob_preset_resolution_config_list *ob_preset_resolution_config_list, ob_error **error);
307+
272308
// The following interfaces are deprecated and are retained here for compatibility purposes.
273309
#define ob_depth_work_mode_list_count ob_depth_work_mode_list_get_count
274310
#define ob_device_preset_list_count ob_device_preset_list_get_count

orbbec_camera/SDK/include/libobsensor/h/ObTypes.h

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ typedef struct ob_depth_work_mode_list_t ob_depth_work_mode_list;
3939
typedef struct ob_device_preset_list_t ob_device_preset_list;
4040
typedef struct ob_filter_config_schema_list_t ob_filter_config_schema_list;
4141
typedef struct ob_device_frame_interleave_list_t ob_device_frame_interleave_list;
42+
typedef struct ob_preset_resolution_config_list_t ob_preset_resolution_config_list;
4243

4344
#define OB_WIDTH_ANY 0
4445
#define OB_HEIGHT_ANY 0
@@ -134,6 +135,7 @@ typedef enum {
134135
OB_SENSOR_IR_LEFT = 6, /**< left IR for stereo camera*/
135136
OB_SENSOR_IR_RIGHT = 7, /**< Right IR for stereo camera*/
136137
OB_SENSOR_RAW_PHASE = 8, /**< Raw Phase */
138+
OB_SENSOR_CONFIDENCE = 9,/**< Confidence */
137139
OB_SENSOR_TYPE_COUNT, /**The total number of sensor types, is not a valid sensor type */
138140
} OBSensorType,
139141
ob_sensor_type;
@@ -152,6 +154,7 @@ typedef enum {
152154
OB_STREAM_IR_LEFT = 6, /**< Left IR stream for stereo camera */
153155
OB_STREAM_IR_RIGHT = 7, /**< Right IR stream for stereo camera */
154156
OB_STREAM_RAW_PHASE = 8, /**< RawPhase Stream */
157+
OB_STREAM_CONFIDENCE = 9, /**< Confidence Stream*/
155158
OB_STREAM_TYPE_COUNT, /**< The total number of stream type,is not a valid stream type */
156159
} OBStreamType,
157160
ob_stream_type;
@@ -172,6 +175,7 @@ typedef enum {
172175
OB_FRAME_IR_LEFT = 8, /**< Left IR frame for stereo camera */
173176
OB_FRAME_IR_RIGHT = 9, /**< Right IR frame for stereo camera */
174177
OB_FRAME_RAW_PHASE = 10, /**< Raw Phase frame*/
178+
OB_FRAME_CONFIDENCE = 11,/**< Confidence frame*/
175179
OB_FRAME_TYPE_COUNT, /**< The total number of frame types, is not a valid frame type */
176180
} OBFrameType,
177181
ob_frame_type;
@@ -227,6 +231,7 @@ typedef enum {
227231
OB_FORMAT_RGBA = 31, /**< RGBA format */
228232
OB_FORMAT_BYR2 = 32, /**< byr2 format */
229233
OB_FORMAT_RW16 = 33, /**< RAW16 format */
234+
OB_FORMAT_Y12C4 = 34, /**< Y12C4 format */
230235
} OBFormat,
231236
ob_format;
232237

@@ -449,6 +454,13 @@ typedef struct {
449454
bool isMirrored; ///< Whether the image frame corresponding to this group of parameters is mirrored
450455
} OBCameraParam, ob_camera_param;
451456

457+
typedef struct {
458+
int16_t width; ///< width
459+
int16_t height; ///< height
460+
int irDecimationFactor; ///< ir decimation factor
461+
int depthDecimationFactor; ///< depth decimation factor
462+
} OBPresetResolutionConfig, ob_preset_resolution_ratio_config;
463+
452464
/**
453465
* @brief calibration parameters
454466
*/
@@ -1829,7 +1841,7 @@ typedef void (*ob_playback_status_changed_callback)(ob_playback_status status, v
18291841
*/
18301842
#define ob_is_video_sensor_type(sensor_type) \
18311843
(sensor_type == OB_SENSOR_COLOR || sensor_type == OB_SENSOR_DEPTH || sensor_type == OB_SENSOR_IR || sensor_type == OB_SENSOR_IR_LEFT \
1832-
|| sensor_type == OB_SENSOR_IR_RIGHT)
1844+
|| sensor_type == OB_SENSOR_IR_RIGHT || sensor_type == OB_SENSOR_CONFIDENCE)
18331845

18341846
/**
18351847
* @brief check if the stream_type is a video stream
@@ -1839,7 +1851,7 @@ typedef void (*ob_playback_status_changed_callback)(ob_playback_status status, v
18391851
*/
18401852
#define ob_is_video_stream_type(stream_type) \
18411853
(stream_type == OB_STREAM_COLOR || stream_type == OB_STREAM_DEPTH || stream_type == OB_STREAM_IR || stream_type == OB_STREAM_IR_LEFT \
1842-
|| stream_type == OB_STREAM_IR_RIGHT || stream_type == OB_STREAM_VIDEO)
1854+
|| stream_type == OB_STREAM_IR_RIGHT || stream_type == OB_STREAM_VIDEO || stream_type == OB_STREAM_CONFIDENCE)
18431855

18441856
/**
18451857
* @brief Check if sensor_type is an IR sensor

orbbec_camera/SDK/include/libobsensor/h/Property.h

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -515,6 +515,36 @@ typedef enum {
515515
*/
516516
OB_DEVICE_PTP_CLOCK_SYNC_ENABLE_BOOL = 223,
517517

518+
/**
519+
* @brief Depth with confidence stream enable
520+
*/
521+
OB_PROP_DEPTH_WITH_CONFIDENCE_STREAM_ENABLE_BOOL = 224,
522+
523+
/**
524+
* @brief Enable or disable confidence stream filter
525+
*/
526+
OB_PROP_CONFIDENCE_STREAM_FILTER_BOOL = 226,
527+
528+
/**
529+
* @brief Confidence stream filter threshold, range [0, 255]
530+
*/
531+
OB_PROP_CONFIDENCE_STREAM_FILTER_THRESHOLD_INT = 227,
532+
533+
/**
534+
* @brief Confidence stream mirror enable
535+
*/
536+
OB_PROP_CONFIDENCE_MIRROR_BOOL = 229,
537+
538+
/**
539+
* @brief Confidence stream flip enable
540+
*/
541+
OB_PROP_CONFIDENCE_FLIP_BOOL = 230,
542+
543+
/**
544+
* @brief Confidence stream rotate angle{0, 90, 180, 270}
545+
*/
546+
OB_PROP_CONFIDENCE_ROTATE_INT = 231,
547+
518548
/**
519549
* @brief Baseline calibration parameters
520550
*/
@@ -604,6 +634,11 @@ typedef enum {
604634
*/
605635
OB_STRUCT_DISP_OFFSET_CONFIG = 1064,
606636

637+
/**
638+
* @brief Preset resolution ratio configuration
639+
*/
640+
OB_STRUCT_PRESET_RESOLUTION_CONFIG = 1069,
641+
607642
/**
608643
* @brief Color camera auto exposure
609644
*/

orbbec_camera/SDK/include/libobsensor/hpp/Device.hpp

Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@ class DevicePresetList;
3030
class OBDepthWorkModeList;
3131
class CameraParamList;
3232
class DeviceFrameInterleaveList;
33+
class PresetResolutionConfigeList;
3334

3435
class Device {
3536
public:
@@ -822,6 +823,18 @@ class Device {
822823
return std::make_shared<DeviceFrameInterleaveList>(list);
823824
}
824825

826+
/**
827+
* @brief Get available frame interleave list
828+
*
829+
* @return DeviceFrameInterleaveList return the available frame interleave list.
830+
*/
831+
std::shared_ptr<PresetResolutionConfigeList> getAvailablePresetResolutionConfigeList() const {
832+
ob_error *error = nullptr;
833+
auto list = ob_device_get_available_preset_resolution_config_list(impl_, &error);
834+
Error::handle(&error);
835+
return std::make_shared<PresetResolutionConfigeList>(list);
836+
}
837+
825838
private:
826839
static void firmwareUpdateCallback(ob_fw_update_state state, const char *message, uint8_t percent, void *userData) {
827840
auto device = static_cast<Device *>(userData);
@@ -1502,4 +1515,42 @@ class DeviceFrameInterleaveList {
15021515
}
15031516
};
15041517

1518+
/**
1519+
* @brief Class representing a list of device Frame Interleave
1520+
*/
1521+
class PresetResolutionConfigeList {
1522+
private:
1523+
ob_preset_resolution_config_list_t *impl_ = nullptr;
1524+
1525+
public:
1526+
explicit PresetResolutionConfigeList(ob_preset_resolution_config_list_t *impl) : impl_(impl) {}
1527+
~PresetResolutionConfigeList() noexcept {
1528+
ob_error *error = nullptr;
1529+
ob_delete_preset_resolution_config_list(impl_, &error);
1530+
Error::handle(&error, false);
1531+
}
1532+
1533+
/**
1534+
* @brief Get the number of device preset resolution ratio in the list
1535+
*/
1536+
uint32_t getCount() {
1537+
ob_error *error = nullptr;
1538+
auto count = ob_device_preset_resolution_config_get_count(impl_, &error);
1539+
Error::handle(&error);
1540+
return count;
1541+
}
1542+
1543+
/*
1544+
* @brief Get the device preset resolution ratio at the specified index
1545+
* @param index the index of the device preset resolution ratio
1546+
* @return OBPresetResolutionConfig the corresponding device preset resolution ratio
1547+
*/
1548+
OBPresetResolutionConfig getPresetResolutionRatioConfig(uint32_t index) {
1549+
ob_error *error = nullptr;
1550+
auto config = ob_device_preset_resolution_config_list_get_item(impl_, index, &error);
1551+
Error::handle(&error);
1552+
return config;
1553+
}
1554+
};
1555+
15051556
} // namespace ob

orbbec_camera/SDK/include/libobsensor/hpp/Filter.hpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -347,7 +347,7 @@ class PointCloudFilter : public Filter {
347347
init(impl);
348348
}
349349

350-
virtual ~PointCloudFilter() noexcept = default;
350+
virtual ~PointCloudFilter() noexcept override = default;
351351

352352
/**
353353
* @brief Set the output pointcloud frame format.
@@ -421,7 +421,7 @@ class Align : public Filter {
421421
setConfigValue("AlignType", static_cast<double>(alignToStreamType));
422422
}
423423

424-
virtual ~Align() noexcept = default;
424+
virtual ~Align() noexcept override = default;
425425

426426
OBStreamType getAlignToStreamType() {
427427
return static_cast<OBStreamType>(static_cast<int>(getConfigValue("AlignType")));
@@ -466,7 +466,7 @@ class FormatConvertFilter : public Filter {
466466
init(impl);
467467
}
468468

469-
virtual ~FormatConvertFilter() noexcept = default;
469+
virtual ~FormatConvertFilter() noexcept override = default;
470470

471471
/**
472472
* @brief Set the format conversion type.
@@ -492,7 +492,7 @@ class HdrMerge : public Filter {
492492
init(impl);
493493
}
494494

495-
virtual ~HdrMerge() noexcept = default;
495+
virtual ~HdrMerge() noexcept override = default;
496496
};
497497

498498
/**
@@ -524,7 +524,7 @@ class SequenceIdFilter : public Filter {
524524
initSequenceIdList();
525525
}
526526

527-
virtual ~SequenceIdFilter() noexcept {
527+
virtual ~SequenceIdFilter() noexcept override {
528528
if(outputSequenceIdList_) {
529529
delete[] outputSequenceIdList_;
530530
outputSequenceIdList_ = nullptr;
@@ -575,7 +575,7 @@ class DecimationFilter : public Filter {
575575
init(impl);
576576
}
577577

578-
virtual ~DecimationFilter() noexcept = default;
578+
virtual ~DecimationFilter() noexcept override = default;
579579

580580
/**
581581
* @brief Set the decimation filter scale value.
@@ -619,7 +619,7 @@ class ThresholdFilter : public Filter {
619619
init(impl);
620620
}
621621

622-
virtual ~ThresholdFilter() noexcept = default;
622+
virtual ~ThresholdFilter() noexcept override = default;
623623

624624
/**
625625
* @brief Get the threshold filter min range.
@@ -682,7 +682,7 @@ class SpatialAdvancedFilter : public Filter {
682682
init(impl);
683683
}
684684

685-
virtual ~SpatialAdvancedFilter() noexcept = default;
685+
virtual ~SpatialAdvancedFilter() noexcept override = default;
686686

687687
/**
688688
* @brief Get the spatial advanced filter alpha range.
@@ -791,7 +791,7 @@ class HoleFillingFilter : public Filter {
791791
init(impl);
792792
}
793793

794-
~HoleFillingFilter() noexcept = default;
794+
~HoleFillingFilter() noexcept override = default;
795795

796796
/**
797797
* @brief Set the HoleFillingFilter mode.
@@ -824,7 +824,7 @@ class NoiseRemovalFilter : public Filter {
824824
init(impl);
825825
}
826826

827-
~NoiseRemovalFilter() noexcept = default;
827+
~NoiseRemovalFilter() noexcept override = default;
828828

829829
/**
830830
* @brief Set the noise removal filter params.
@@ -895,7 +895,7 @@ class TemporalFilter : public Filter {
895895
init(impl);
896896
}
897897

898-
~TemporalFilter() noexcept = default;
898+
~TemporalFilter() noexcept override = default;
899899

900900
/**
901901
* @brief Get the TemporalFilter diffscale range.
@@ -962,7 +962,7 @@ class DisparityTransform : public Filter {
962962
init(impl);
963963
}
964964

965-
~DisparityTransform() noexcept = default;
965+
~DisparityTransform() noexcept override = default;
966966
};
967967

968968
class OBFilterList {

orbbec_camera/SDK/include/libobsensor/hpp/Frame.hpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -553,6 +553,28 @@ class IRFrame : public VideoFrame {
553553
~IRFrame() noexcept override = default;
554554
};
555555

556+
/**
557+
* @brief Define the ConfidenceFrame class, which inherits from the VideoFrame class
558+
*
559+
*/
560+
class ConfidenceFrame : public VideoFrame {
561+
562+
public:
563+
/**
564+
* @brief Construct a new ConfidenceFrame object with a given pointer to the internal frame object.
565+
*
566+
* @attention After calling this constructor, the frame object will own the internal frame object, and the internal frame object will be deleted when the
567+
* frame object is destroyed.
568+
* @attention The internal frame object should not be deleted by the caller.
569+
* @attention Please use the FrameFactory to create a Frame object.
570+
*
571+
* @param impl The pointer to the internal frame object.
572+
*/
573+
explicit ConfidenceFrame(const ob_frame *impl) : VideoFrame(impl){};
574+
575+
~ConfidenceFrame() noexcept override = default;
576+
};
577+
556578
/**
557579
* @brief Define the PointsFrame class, which inherits from the Frame class
558580
* @brief The PointsFrame class is used to obtain pointcloud data and point cloud information.
@@ -1036,6 +1058,8 @@ template <typename T> bool Frame::is() const {
10361058
return (typeid(T) == typeid(DepthFrame) || typeid(T) == typeid(VideoFrame));
10371059
case OB_FRAME_COLOR:
10381060
return (typeid(T) == typeid(ColorFrame) || typeid(T) == typeid(VideoFrame));
1061+
case OB_FRAME_CONFIDENCE:
1062+
return (typeid(T) == typeid(ConfidenceFrame) || typeid(T) == typeid(VideoFrame));
10391063
case OB_FRAME_GYRO:
10401064
return (typeid(T) == typeid(GyroFrame));
10411065
case OB_FRAME_ACCEL:

0 commit comments

Comments
 (0)