Skip to content

Commit

Permalink
update to v2.0.7
Browse files Browse the repository at this point in the history
  • Loading branch information
jj committed Oct 21, 2024
1 parent 99d35d9 commit 0de68ca
Show file tree
Hide file tree
Showing 60 changed files with 1,086 additions and 3,763 deletions.
1,490 changes: 745 additions & 745 deletions .gitignore

Large diffs are not rendered by default.

141 changes: 85 additions & 56 deletions README.MD

Large diffs are not rendered by default.

Binary file added docs/images/image10.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/images/image7.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/images/image8.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/images/image9.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
2 changes: 1 addition & 1 deletion orbbec_camera/SDK/include/libobsensor/h/Device.h
Original file line number Diff line number Diff line change
Expand Up @@ -632,7 +632,7 @@ OB_EXPORT void ob_delete_camera_param_list(ob_camera_param_list *param_list, ob_
#define ob_device_info_uid ob_device_info_get_uid
#define ob_device_info_serial_number ob_device_info_get_serial_number
#define ob_device_info_firmware_version ob_device_info_get_firmware_version
#define ob_device_info_connection_type ob_device_list_get_device_connection_type
#define ob_device_info_connection_type ob_device_info_get_connection_type
#define ob_device_info_ip_address ob_device_info_get_ip_address
#define ob_device_info_hardware_version ob_device_info_get_hardware_version
#define ob_device_info_supported_min_sdk_version ob_device_info_get_supported_min_sdk_version
Expand Down
2 changes: 1 addition & 1 deletion orbbec_camera/SDK/include/libobsensor/hpp/Context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ class Context {
* @brief Creates a network device with the specified IP address and port.
*
* @param[in] address The IP address, ipv4 only. such as "192.168.1.10"
* @param[in] port The port number.
* @param[in] port The port number, currently only support 8090
* @return std::shared_ptr<Device> The created device object.
*/
std::shared_ptr<Device> createNetDevice(const char *address, uint16_t port) const {
Expand Down
2 changes: 1 addition & 1 deletion orbbec_camera/SDK/include/libobsensor/hpp/Frame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,7 +261,7 @@ class Frame : public std::enable_shared_from_this<Frame> {
ob_error *error = nullptr;
auto profile = ob_frame_get_stream_profile(impl_, &error);
Error::handle(&error);
return std::make_shared<StreamProfile>(profile);
return StreamProfileFactory::create(profile);
}

/**
Expand Down
50 changes: 40 additions & 10 deletions orbbec_camera/SDK/include/libobsensor/hpp/StreamProfile.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

#include "Types.hpp"
#include "libobsensor/h/StreamProfile.h"
#include "libobsensor/h/Error.h"
#include <iostream>
#include <memory>

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

public:
explicit StreamProfile(const ob_stream_profile_t *impl) : impl_(impl) {}

StreamProfile(StreamProfile &streamProfile) = delete;
StreamProfile(StreamProfile &streamProfile) = delete;
StreamProfile &operator=(StreamProfile &streamProfile) = delete;

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

return std::static_pointer_cast<T>(shared_from_this());
return std::dynamic_pointer_cast<T>(shared_from_this());
}

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

public:
// The following interfaces are deprecated and are retained here for compatibility purposes.
OBFormat format() const {
return getFormat();
Expand All @@ -132,6 +130,9 @@ class StreamProfile : public std::enable_shared_from_this<StreamProfile> {
OBStreamType type() const {
return getType();
}

protected:
explicit StreamProfile(const ob_stream_profile_t *impl) : impl_(impl) {}
};

/**
Expand Down Expand Up @@ -351,6 +352,33 @@ template <typename T> bool StreamProfile::is() const {
return false;
}

class StreamProfileFactory {
public:
static std::shared_ptr<StreamProfile> create(const ob_stream_profile_t *impl) {
ob_error *error = nullptr;
const auto type = ob_stream_profile_get_type(impl, &error);
Error::handle(&error);
switch(type) {
case OB_STREAM_IR:
case OB_STREAM_IR_LEFT:
case OB_STREAM_IR_RIGHT:
case OB_STREAM_DEPTH:
case OB_STREAM_COLOR:
case OB_STREAM_VIDEO:
return std::make_shared<VideoStreamProfile>(impl);
case OB_STREAM_ACCEL:
return std::make_shared<AccelStreamProfile>(impl);
case OB_STREAM_GYRO:
return std::make_shared<GyroStreamProfile>(impl);
default: {
ob_error *err = ob_create_error(OB_STATUS_ERROR, "Unsupported stream type.", "StreamProfileFactory::create", "", OB_EXCEPTION_TYPE_INVALID_VALUE);
Error::handle(&err);
return nullptr;
}
}
}
};

class StreamProfileList {
protected:
const ob_stream_profile_list_t *impl_;
Expand Down Expand Up @@ -385,7 +413,7 @@ class StreamProfileList {
ob_error *error = nullptr;
auto profile = ob_stream_profile_list_get_profile(impl_, index, &error);
Error::handle(&error);
return std::make_shared<StreamProfile>(profile);
return StreamProfileFactory::create(profile);
}

/**
Expand All @@ -403,7 +431,8 @@ class StreamProfileList {
ob_error *error = nullptr;
auto profile = ob_stream_profile_list_get_video_stream_profile(impl_, width, height, format, fps, &error);
Error::handle(&error);
return std::make_shared<VideoStreamProfile>(profile);
auto vsp = StreamProfileFactory::create(profile);
return vsp->as<VideoStreamProfile>();
}

/**
Expand All @@ -417,7 +446,8 @@ class StreamProfileList {
ob_error *error = nullptr;
auto profile = ob_stream_profile_list_get_accel_stream_profile(impl_, fullScaleRange, sampleRate, &error);
Error::handle(&error);
return std::make_shared<AccelStreamProfile>(profile);
auto asp = StreamProfileFactory::create(profile);
return asp->as<AccelStreamProfile>();
}

/**
Expand All @@ -431,7 +461,8 @@ class StreamProfileList {
ob_error *error = nullptr;
auto profile = ob_stream_profile_list_get_gyro_stream_profile(impl_, fullScaleRange, sampleRate, &error);
Error::handle(&error);
return std::make_shared<GyroStreamProfile>(profile);
auto gsp = StreamProfileFactory::create(profile);
return gsp->as<GyroStreamProfile>();
}

public:
Expand All @@ -442,4 +473,3 @@ class StreamProfileList {
};

} // namespace ob

Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file modified orbbec_camera/SDK/lib/arm64/libOrbbecSDK.so
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file modified orbbec_camera/SDK/lib/x64/libOrbbecSDK.so
Binary file not shown.
18 changes: 9 additions & 9 deletions orbbec_camera/config/camera_params.yaml
Original file line number Diff line number Diff line change
@@ -1,33 +1,33 @@
# common params
depth_registration: false
depth_registration: true
enable_point_cloud: false
enable_colored_point_cloud: false
device_preset: "High Accuracy"
laser_on_off_mode: 1 # 0: off, 1: on-off, 1: off-on
laser_on_off_mode: 0 # 0: off, 1: on-off, 1: off-on
time_domain: "global" # global, device, system
enable_sync_host_time: false
frames_per_trigger: 2
frames_per_trigger: 1

# When 3D reconstruction mode is enabled:
# - The laser will switch to on-off mode
# - IR images without the laser will be used for SLAM localization
# - Depth images with the laser will be used because they provide better depth quality
enable_3d_reconstruction_mode: true
enable_3d_reconstruction_mode: false

# color params
enable_color: true
color_width: 640
color_height: 480
color_fps: 90
color_fps: 30
color_format: "YUYV"
enable_color_auto_exposure: false
enable_color_auto_exposure: true
color_exposure: 50 # 5ms
color_gain: -1 # -1 default

# depth params
depth_width: 640
depth_height: 480
depth_fps: 90
depth_fps: 30
depth_format: "Y16"

# ir exposure
Expand All @@ -39,12 +39,12 @@ ir_gain: 40
enable_left_ir: true
left_ir_width: 640
left_ir_height: 480
left_ir_fps: 90
left_ir_fps: 30
left_ir_format: "Y8"

#right ir params
enable_right_ir: true
right_ir_width: 640
right_ir_height: 480
right_ir_fps: 90
right_ir_fps: 30
right_ir_format: "Y8"
2 changes: 1 addition & 1 deletion orbbec_camera/include/orbbec_camera/constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#define OB_ROS_MAJOR_VERSION 2
#define OB_ROS_MINOR_VERSION 0
#define OB_ROS_PATCH_VERSION 5
#define OB_ROS_PATCH_VERSION 7

#ifndef STRINGIFY
#define STRINGIFY(arg) #arg
Expand Down
16 changes: 16 additions & 0 deletions orbbec_camera/include/orbbec_camera/ob_camera_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@
#include "orbbec_camera/image_publisher.h"
#include "jpeg_decoder.h"
#include <std_msgs/msg/string.hpp>
#include <fcntl.h>

#if defined(ROS_JAZZY) || defined(ROS_IRON)
#include <cv_bridge/cv_bridge.hpp>
Expand Down Expand Up @@ -94,6 +95,8 @@
(static_cast<std::ostringstream&&>(std::ostringstream() << getNamespaceStr() << "_odom_frame")) \
.str()

#define DEVICE_PATH "/dev/camsync"

namespace orbbec_camera {
using GetDeviceInfo = orbbec_camera_msgs::srv::GetDeviceInfo;
using Extrinsics = orbbec_camera_msgs::msg::Extrinsics;
Expand Down Expand Up @@ -129,6 +132,11 @@ const std::map<OBStreamType, OBFrameType> STREAM_TYPE_TO_FRAME_TYPE = {
{OB_STREAM_ACCEL, OB_FRAME_ACCEL},
};

typedef struct {
uint8_t mode;
uint16_t fps;
} cs_param_t;

class OBCameraNode {
public:
OBCameraNode(rclcpp::Node* node, std::shared_ptr<ob::Device> device,
Expand All @@ -152,6 +160,11 @@ class OBCameraNode {

void startIMU();

int openSocSyncPwmTrigger(uint16_t fps);
int closeSocSyncPwmTrigger();
void startGmslTrigger();
void stopGmslTrigger();

private:
struct IMUData {
IMUData() = default;
Expand Down Expand Up @@ -539,6 +552,9 @@ class OBCameraNode {
int hdr_merge_gain_1_ = -1;
int hdr_merge_exposure_2_ = -1;
int hdr_merge_gain_2_ = -1;
int gmsl_trigger_fd_ = -1;
int gmsl_trigger_fps_ = -1;
bool enable_gmsl_trigger_ = false;

rclcpp::Publisher<std_msgs::msg::String>::SharedPtr filter_status_pub_;
nlohmann::json filter_status_;
Expand Down
126 changes: 0 additions & 126 deletions orbbec_camera/launch/astra.launch.py

This file was deleted.

Loading

0 comments on commit 0de68ca

Please sign in to comment.