Skip to content

Commit 0de68ca

Browse files
author
jj
committed
update to v2.0.7
1 parent 99d35d9 commit 0de68ca

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

60 files changed

+1086
-3763
lines changed

.gitignore

Lines changed: 745 additions & 745 deletions
Large diffs are not rendered by default.

README.MD

Lines changed: 85 additions & 56 deletions
Large diffs are not rendered by default.

docs/images/image10.png

256 KB
Loading

docs/images/image7.png

126 KB
Loading

docs/images/image8.png

270 KB
Loading

docs/images/image9.png

154 KB
Loading

orbbec_camera/SDK/include/libobsensor/h/Device.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -632,7 +632,7 @@ OB_EXPORT void ob_delete_camera_param_list(ob_camera_param_list *param_list, ob_
632632
#define ob_device_info_uid ob_device_info_get_uid
633633
#define ob_device_info_serial_number ob_device_info_get_serial_number
634634
#define ob_device_info_firmware_version ob_device_info_get_firmware_version
635-
#define ob_device_info_connection_type ob_device_list_get_device_connection_type
635+
#define ob_device_info_connection_type ob_device_info_get_connection_type
636636
#define ob_device_info_ip_address ob_device_info_get_ip_address
637637
#define ob_device_info_hardware_version ob_device_info_get_hardware_version
638638
#define ob_device_info_supported_min_sdk_version ob_device_info_get_supported_min_sdk_version

orbbec_camera/SDK/include/libobsensor/hpp/Context.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ class Context {
101101
* @brief Creates a network device with the specified IP address and port.
102102
*
103103
* @param[in] address The IP address, ipv4 only. such as "192.168.1.10"
104-
* @param[in] port The port number.
104+
* @param[in] port The port number, currently only support 8090
105105
* @return std::shared_ptr<Device> The created device object.
106106
*/
107107
std::shared_ptr<Device> createNetDevice(const char *address, uint16_t port) const {

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -261,7 +261,7 @@ class Frame : public std::enable_shared_from_this<Frame> {
261261
ob_error *error = nullptr;
262262
auto profile = ob_frame_get_stream_profile(impl_, &error);
263263
Error::handle(&error);
264-
return std::make_shared<StreamProfile>(profile);
264+
return StreamProfileFactory::create(profile);
265265
}
266266

267267
/**

orbbec_camera/SDK/include/libobsensor/hpp/StreamProfile.hpp

Lines changed: 40 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99

1010
#include "Types.hpp"
1111
#include "libobsensor/h/StreamProfile.h"
12+
#include "libobsensor/h/Error.h"
1213
#include <iostream>
1314
#include <memory>
1415

@@ -19,9 +20,7 @@ class StreamProfile : public std::enable_shared_from_this<StreamProfile> {
1920
const ob_stream_profile_t *impl_ = nullptr;
2021

2122
public:
22-
explicit StreamProfile(const ob_stream_profile_t *impl) : impl_(impl) {}
23-
24-
StreamProfile(StreamProfile &streamProfile) = delete;
23+
StreamProfile(StreamProfile &streamProfile) = delete;
2524
StreamProfile &operator=(StreamProfile &streamProfile) = delete;
2625

2726
StreamProfile(StreamProfile &&streamProfile) noexcept : impl_(streamProfile.impl_) {
@@ -106,7 +105,7 @@ class StreamProfile : public std::enable_shared_from_this<StreamProfile> {
106105
throw std::runtime_error("Unsupported operation. Object's type is not the required type.");
107106
}
108107

109-
return std::static_pointer_cast<T>(shared_from_this());
108+
return std::dynamic_pointer_cast<T>(shared_from_this());
110109
}
111110

112111
/**
@@ -123,7 +122,6 @@ class StreamProfile : public std::enable_shared_from_this<StreamProfile> {
123122
return std::static_pointer_cast<const T>(shared_from_this());
124123
}
125124

126-
public:
127125
// The following interfaces are deprecated and are retained here for compatibility purposes.
128126
OBFormat format() const {
129127
return getFormat();
@@ -132,6 +130,9 @@ class StreamProfile : public std::enable_shared_from_this<StreamProfile> {
132130
OBStreamType type() const {
133131
return getType();
134132
}
133+
134+
protected:
135+
explicit StreamProfile(const ob_stream_profile_t *impl) : impl_(impl) {}
135136
};
136137

137138
/**
@@ -351,6 +352,33 @@ template <typename T> bool StreamProfile::is() const {
351352
return false;
352353
}
353354

355+
class StreamProfileFactory {
356+
public:
357+
static std::shared_ptr<StreamProfile> create(const ob_stream_profile_t *impl) {
358+
ob_error *error = nullptr;
359+
const auto type = ob_stream_profile_get_type(impl, &error);
360+
Error::handle(&error);
361+
switch(type) {
362+
case OB_STREAM_IR:
363+
case OB_STREAM_IR_LEFT:
364+
case OB_STREAM_IR_RIGHT:
365+
case OB_STREAM_DEPTH:
366+
case OB_STREAM_COLOR:
367+
case OB_STREAM_VIDEO:
368+
return std::make_shared<VideoStreamProfile>(impl);
369+
case OB_STREAM_ACCEL:
370+
return std::make_shared<AccelStreamProfile>(impl);
371+
case OB_STREAM_GYRO:
372+
return std::make_shared<GyroStreamProfile>(impl);
373+
default: {
374+
ob_error *err = ob_create_error(OB_STATUS_ERROR, "Unsupported stream type.", "StreamProfileFactory::create", "", OB_EXCEPTION_TYPE_INVALID_VALUE);
375+
Error::handle(&err);
376+
return nullptr;
377+
}
378+
}
379+
}
380+
};
381+
354382
class StreamProfileList {
355383
protected:
356384
const ob_stream_profile_list_t *impl_;
@@ -385,7 +413,7 @@ class StreamProfileList {
385413
ob_error *error = nullptr;
386414
auto profile = ob_stream_profile_list_get_profile(impl_, index, &error);
387415
Error::handle(&error);
388-
return std::make_shared<StreamProfile>(profile);
416+
return StreamProfileFactory::create(profile);
389417
}
390418

391419
/**
@@ -403,7 +431,8 @@ class StreamProfileList {
403431
ob_error *error = nullptr;
404432
auto profile = ob_stream_profile_list_get_video_stream_profile(impl_, width, height, format, fps, &error);
405433
Error::handle(&error);
406-
return std::make_shared<VideoStreamProfile>(profile);
434+
auto vsp = StreamProfileFactory::create(profile);
435+
return vsp->as<VideoStreamProfile>();
407436
}
408437

409438
/**
@@ -417,7 +446,8 @@ class StreamProfileList {
417446
ob_error *error = nullptr;
418447
auto profile = ob_stream_profile_list_get_accel_stream_profile(impl_, fullScaleRange, sampleRate, &error);
419448
Error::handle(&error);
420-
return std::make_shared<AccelStreamProfile>(profile);
449+
auto asp = StreamProfileFactory::create(profile);
450+
return asp->as<AccelStreamProfile>();
421451
}
422452

423453
/**
@@ -431,7 +461,8 @@ class StreamProfileList {
431461
ob_error *error = nullptr;
432462
auto profile = ob_stream_profile_list_get_gyro_stream_profile(impl_, fullScaleRange, sampleRate, &error);
433463
Error::handle(&error);
434-
return std::make_shared<GyroStreamProfile>(profile);
464+
auto gsp = StreamProfileFactory::create(profile);
465+
return gsp->as<GyroStreamProfile>();
435466
}
436467

437468
public:
@@ -442,4 +473,3 @@ class StreamProfileList {
442473
};
443474

444475
} // namespace ob
445-

0 commit comments

Comments
 (0)