Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Pre_release_v281_iron #406

Merged
merged 30 commits into from
Sep 13, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
30 commits
Select commit Hold shift + click to select a range
3e959f9
Added shebang so it's executable (#316)
mattwilliamson May 26, 2023
c77c4e9
Stereo updates (#320)
Serafadam May 26, 2023
40dec09
add brightness filter (#284)
kaichie Jun 16, 2023
e8defa1
Pipeline generation as plugins (#321)
Serafadam Jun 16, 2023
4868570
Update pull_request_template.md
saching13 Jun 21, 2023
657068b
3D bounding boxes in Humble (#336)
Serafadam Jun 21, 2023
131bff4
Qos overrides (#339)
Serafadam Jun 23, 2023
ecf772b
Ros time update humble (#340)
Serafadam Jun 26, 2023
6693cfe
Pre release v2.7.4 (#343)
Serafadam Jun 26, 2023
0a977db
Imu sync fix humble (#357)
Serafadam Aug 7, 2023
f1c0656
Add camera image orientation param (#364)
jasiex01 Aug 11, 2023
a9a80b1
Performance update humble (#359)
Serafadam Aug 17, 2023
54a8504
Feature tracker humble (#366)
Serafadam Aug 18, 2023
032f69e
Handle USB speed when usb id is specified (#372)
xouillet Aug 21, 2023
c3b7372
Change misleading error to a clearer message (#373)
xouillet Aug 21, 2023
4b3fe01
Minor updates Humble (#375)
Serafadam Aug 21, 2023
98ea647
Watchdog humble (#377)
Serafadam Aug 30, 2023
a29af54
Depth alignment update humble (#380)
Serafadam Aug 31, 2023
9af7cbb
Synced_stereo_humble (#379)
Serafadam Aug 31, 2023
a35c7c3
Lazy Publishing Humble (#381)
Serafadam Aug 31, 2023
eca7bae
Urdf loader humble (#347)
Serafadam Sep 1, 2023
e544cb9
Add exposure offset (#382)
Serafadam Sep 1, 2023
7233130
Pre-release 2.8.0 (#384)
Serafadam Sep 5, 2023
038f107
Stereo_socket_order_humble (#394)
Serafadam Sep 11, 2023
365d002
update socket logic (#400)
Serafadam Sep 11, 2023
dbcadce
get and set DisparityToDepthUseSpecTranslation (#397)
BriceRenaudeau Sep 12, 2023
96c4fd2
Update sensor names & readme (#403)
Serafadam Sep 12, 2023
715d480
Pre_release_v281_humble (#404)
Serafadam Sep 13, 2023
51565f6
Merge branch 'humble' of github.com:luxonis/depthai-ros into pre_rele…
Serafadam Sep 13, 2023
9db47c8
fix stereo param handler
Serafadam Sep 13, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
239 changes: 235 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,8 @@ docker run -it -v /dev/:/dev/ --privileged -e DISPLAY -v /tmp/.X11-unix:/tmp/.X1

Currently, recommended way to launch cameras is to use executables from depthai_ros_driver package.

This runs your camera as a ROS2 Component and gives you the ability to customize your camera using ROS parameters.
This runs your camera as a ROS2 Component/ROS Nodelet and gives you the ability to customize your camera using ROS parameters.
Main API difference between ROS2 and ROS1 is that parameter names use different convention - parameters in ROS2 are namespaced using `.` and parameters in ROS1 are namespaced using `_`, for example in ROS2: `camera.i_pipeline_type`, ROS1 `camera_i_pipeline_type`. For sake of simplicity, this Readme uses ROS2 convention. List of all available parameters with their default values can be found at the bottom of Readme.
Paramerers that begin with `r_` can be freely modified during runtime, for example with rqt.
Parameters that begin with `i_` are set when camera is initializing, to change them you have to call `stop` and `start` services. This can be used to hot swap NNs during runtime, changing resolutions, etc. Below you can see some examples:

Expand Down Expand Up @@ -166,19 +167,40 @@ It is also possible to set custom URDF path (for now only absolute path works) a
**NOTE ON IMU EXTRINSICS**
If your camera has uncalibrated IMU, a warning will be shown, and IMU will be published with zero rotation and translation. You can override this behavior by setting `camera.i_tf_imu_from_descr`: true. This will publish default IMU extrinsics from URDF based on camera model.


#### Available sensors and their resolutions:

* IMX378 - {"12MP", "4K", "1080P"}, default 1080P
* OV9282 - {"800P", "720P", "400P"}, default 800P
* OV9782 - {"800P", "720P", "400P"}, default 800P
* OV9281 - {"800P", "720P", "400P"}, default 800P
* IMX214 - {"13MP", "12MP", "4K", "1080P"}, default 1080P
* IMX412 - {"13MP", "12MP", "4K", "1080P"}, default 1080P
* OV7750 - {"480P", "400P"}, default 480P
* OV7251 - {"480P", "400P"}, default 480P
* IMX477 - {"12MP", "4K", "1080P"}, default 1080P
* IMX577 - {"12MP", "4K", "1080P"}, default 1080P
* AR0234 - {"1200P"}, default 1200P
* IMX582 - {"48MP", "12MP", "4K"}, default 4K
* LCM48 - {"48MP", "12MP", "4K"}, default 4K

#### Setting RGB parameters
![](docs/param_rgb.gif)

By default RGB camera outputs `ISP` frame. To set custom width and height of output image, you can set `i_isp_num` and `i_isp_den` which scale image dimensions (2 and 3 by default, so from 1920x1080 to 1280x720), note for RGBD alignment to work resulting width and height must be divisible by 16.

Additionally you can set `i.output_isp: false` to use `video` output and set custom size using `i_width` and `i_height` parameters.
![](docs/param_rgb.gif)

#### Setting Stereo parameters
![](docs/param_stereo.gif)
##### Depth alignment
When setting `stereo.i_align_depth: true`, stereo output is aligned to board socket specified by `stereo.i_board_socket_id` parameter (by default 0/CAM_A)

You can enable rectified Stereo streams by setting, for example in the case of right stream `i_publish_right_rect: true`. You can also set `i_publish_synced_rect_pair: true` to get both images with the same timestamps.

##### Stereo socket order
By default, right camera is treated as first when used for stereo computation, which is reflected in CameraInfo messages. If you want to reverse that logic, set `stereo.i_reverse_stereo_socket_order: true` (this can be also set for individual sensors).

##### Custom Sensor sockets

Configuration of which sensors are used for computing stereo pair can be done either programatically, by specifying them in a constructor of a Stereo node (for example when building a custom pipeline), or via parameters - `stereo.i_left_socket_id`/`stereo.i_right_socket_id`. Please note that currently if you want to use rgb/center socket instead of one of the given pairs you will need to build a custom pipeline for that.
Expand Down Expand Up @@ -302,7 +324,6 @@ an example can be seen by running `ros2 launch depthai_filters example_wls_filt
- FeatureTrackerOverlay - publishes Tracked Features overlay based on features and images coming from the driver
- Features3D - uses depth image to republish features as 3D pointcloud


### Using external sources for NN inference or Stereo Depth

There is a possibility of using external image topics as input for NNs or Depth calculation.
Expand Down Expand Up @@ -382,4 +403,214 @@ For easier development inside isolated workspace, one can use Visual Studio Code
- Create separate workspace
- Clone repository into src
- Copy `.devcontainer` directory into main workspace directory
- Open workspace directory in VSCode
- Open workspace directory in VSCode

### List of parameters:
```yaml
/oak:
ros__parameters:
camera:
i_calibration_dump: false
i_enable_imu: true
i_enable_ir: true
i_external_calibration_path: ''
i_floodlight_brightness: 0
i_ip: ''
i_laser_dot_brightness: 800
i_mx_id: ''
i_nn_type: spatial
i_pipeline_dump: false
i_pipeline_type: RGBD
i_publish_tf_from_calibration: false
i_tf_base_frame: oak
i_tf_cam_pitch: '0.0'
i_tf_cam_pos_x: '0.0'
i_tf_cam_pos_y: '0.0'
i_tf_cam_pos_z: '0.0'
i_tf_cam_roll: '0.0'
i_tf_cam_yaw: '0.0'
i_tf_camera_model: ''
i_tf_camera_name: oak
i_tf_custom_urdf_location: ''
i_tf_custom_xacro_args: ''
i_tf_imu_from_descr: 'false'
i_tf_parent_frame: oak-d-base-frame
i_usb_port_id: ''
i_usb_speed: SUPER_PLUS
diagnostic_updater:
period: 1.0
imu:
i_acc_cov: 0.0
i_acc_freq: 400
i_batch_report_threshold: 5
i_enable_rotation: false
i_get_base_device_timestamp: false
i_gyro_cov: 0.0
i_gyro_freq: 400
i_mag_cov: 0.0
i_max_batch_reports: 10
i_message_type: IMU
i_rot_cov: -1.0
i_sync_method: LINEAR_INTERPOLATE_ACCEL
i_update_ros_base_time_on_ros_msg: false
left:
i_add_exposure_offset: false
i_board_socket_id: 1
i_calibration_file: ''
i_disable_node: false
i_enable_feature_tracker: false
i_enable_lazy_publisher: true
i_exposure_offset: 0
i_fps: 30.0
i_fsync_continuous: false
i_fsync_trigger: false
i_get_base_device_timestamp: false
i_height: 720
i_low_bandwidth: false
i_low_bandwidth_quality: 50
i_max_q_size: 30
i_publish_topic: false
i_resolution: '720'
i_reverse_stereo_socket_order: false
i_sensor_img_orientation: NORMAL
i_set_isp3a_fps: false
i_simulate_from_topic: false
i_simulated_topic_name: ''
i_update_ros_base_time_on_ros_msg: false
i_width: 1280
r_exposure: 1000
r_iso: 800
r_set_man_exposure: false
nn:
i_disable_resize: false
i_enable_passthrough: false
i_enable_passthrough_depth: false
i_get_base_device_timestamp: false
i_num_inference_threads: 2
i_num_pool_frames: 4
i_update_ros_base_time_on_ros_msg: false
rgb:
i_add_exposure_offset: false
i_board_socket_id: 0
i_calibration_file: ''
i_disable_node: false
i_enable_feature_tracker: false
i_enable_lazy_publisher: true
i_enable_preview: false
i_exposure_offset: 0
i_fps: 30.0
i_fsync_continuous: false
i_fsync_trigger: false
i_get_base_device_timestamp: false
i_height: 720
i_interleaved: false
i_isp_den: 3
i_isp_num: 2
i_keep_preview_aspect_ratio: true
i_low_bandwidth: false
i_low_bandwidth_quality: 50
i_max_q_size: 30
i_output_isp: true
i_preview_height: 300
i_preview_size: 300
i_preview_width: 300
i_publish_topic: true
i_resolution: 1080p
i_reverse_stereo_socket_order: false
i_sensor_img_orientation: NORMAL
i_set_isp3a_fps: false
i_set_isp_scale: true
i_simulate_from_topic: false
i_simulated_topic_name: ''
i_update_ros_base_time_on_ros_msg: false
i_width: 1280
r_exposure: 20000
r_focus: 1
r_iso: 800
r_set_man_exposure: false
r_set_man_focus: false
r_set_man_whitebalance: false
r_whitebalance: 3300
right:
i_add_exposure_offset: false
i_board_socket_id: 2
i_calibration_file: ''
i_disable_node: false
i_enable_feature_tracker: false
i_enable_lazy_publisher: true
i_exposure_offset: 0
i_fps: 30.0
i_fsync_continuous: false
i_fsync_trigger: false
i_get_base_device_timestamp: false
i_height: 720
i_low_bandwidth: false
i_low_bandwidth_quality: 50
i_max_q_size: 30
i_publish_topic: false
i_resolution: '720'
i_reverse_stereo_socket_order: false
i_sensor_img_orientation: NORMAL
i_set_isp3a_fps: false
i_simulate_from_topic: false
i_simulated_topic_name: ''
i_update_ros_base_time_on_ros_msg: false
i_width: 1280
r_exposure: 1000
r_iso: 800
r_set_man_exposure: false
stereo:
i_add_exposure_offset: false
i_align_depth: true
i_bilateral_sigma: 0
i_board_socket_id: 0
i_depth_filter_size: 5
i_depth_preset: HIGH_ACCURACY
i_disparity_width: DISPARITY_96
i_enable_alpha_scaling: false
i_enable_brightness_filter: false
i_enable_companding: false
i_enable_decimation_filter: false
i_enable_disparity_shift: false
i_enable_distortion_correction: false
i_enable_lazy_publisher: true
i_enable_spatial_filter: false
i_enable_speckle_filter: false
i_enable_temporal_filter: false
i_enable_threshold_filter: false
i_exposure_offset: 0
i_extended_disp: false
i_get_base_device_timestamp: false
i_height: 720
i_left_rect_add_exposure_offset: false
i_left_rect_enable_feature_tracker: false
i_left_rect_exposure_offset: 0
i_left_rect_low_bandwidth: false
i_left_rect_low_bandwidth_quality: 50
i_left_socket_id: 1
i_low_bandwidth: false
i_low_bandwidth_quality: 50
i_lr_check: true
i_lrc_threshold: 10
i_max_q_size: 30
i_output_disparity: false
i_publish_left_rect: false
i_publish_right_rect: false
i_publish_synced_rect_pair: false
i_publish_topic: true
i_rectify_edge_fill_color: 0
i_reverse_stereo_socket_order: false
i_right_rect_add_exposure_offset: false
i_right_rect_enable_feature_tracker: false
i_right_rect_exposure_offset: 0
i_right_rect_low_bandwidth: false
i_right_rect_low_bandwidth_quality: 50
i_right_socket_id: 2
i_set_input_size: false
i_socket_name: rgb
i_stereo_conf_threshold: 240
i_subpixel: false
i_update_ros_base_time_on_ros_msg: false
i_width: 1280
use_sim_time: false
```
9 changes: 9 additions & 0 deletions depthai-ros/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,15 @@
Changelog for package depthai-ros
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.8.1 (2023-09-12)
-------------------

* Added support for OpenCV Stereo order convention
* Added disparity to depth use spec translation parameter
* Updated sensor socket logic
* Fixed issues when running robot_state_publisher as component
* Added missing tf2 dependencies

2.8.0 (2023-09-01)
-------------------
* Add camera image orientation param
Expand Down
2 changes: 1 addition & 1 deletion depthai-ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 3.10.2) # CMake version in Ubuntu 18.04 LTS

project(depthai-ros VERSION 2.8.0 LANGUAGES CXX C)
project(depthai-ros VERSION 2.8.1 LANGUAGES CXX C)

set(CMAKE_CXX_STANDARD 14)

Expand Down
2 changes: 1 addition & 1 deletion depthai-ros/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>depthai-ros</name>
<version>2.8.0</version>
<version>2.8.1</version>
<description>The depthai-ros package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
Expand Down
8 changes: 7 additions & 1 deletion depthai_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 3.10.2) # CMake version in Ubuntu 18.04 LTS
set(CMAKE_POSITION_INDEPENDENT_CODE ON)

project(depthai_bridge VERSION 2.8.0 LANGUAGES CXX C)
project(depthai_bridge VERSION 2.8.1 LANGUAGES CXX C)

set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
Expand Down Expand Up @@ -38,6 +38,9 @@ find_package(stereo_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(vision_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(composition_interfaces REQUIRED)

set(dependencies
camera_info_manager
Expand All @@ -50,6 +53,9 @@ set(dependencies
std_msgs
vision_msgs
tf2_ros
tf2_geometry_msgs
tf2
composition_interfaces
)

include_directories(
Expand Down
31 changes: 24 additions & 7 deletions depthai_bridge/include/depthai_bridge/ImageConverter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,7 @@ namespace ImageMsgs = sensor_msgs::msg;
using ImagePtr = ImageMsgs::Image::SharedPtr;

using TimePoint = std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration>;
ImageMsgs::CameraInfo calibrationToCameraInfo(dai::CalibrationHandler calibHandler,
dai::CameraBoardSocket cameraId,
int width = -1,
int height = -1,
Point2f topLeftPixelId = Point2f(),
Point2f bottomRightPixelId = Point2f());

class ImageConverter {
public:
// ImageConverter() = default;
Expand All @@ -55,9 +50,29 @@ class ImageConverter {
_updateRosBaseTimeOnToRosMsg = update;
}

/**
* @brief Sets converter behavior to convert from bitstream to raw data.
* @param srcType: The type of the bitstream data used for conversion.
*/
void convertFromBitstream(dai::RawImgFrame::Type srcType);

/**
* @brief Sets exposure offset when getting timestamps from the message.
* @param offset: The exposure offset to be added to the timestamp.
*/
void addExposureOffset(dai::CameraExposureOffset& offset);
void convertDispToDepth();

/**
* @brief Sets converter behavior to convert from disparity to depth when converting messages from bitstream.
* @param baseline: The baseline of the stereo pair.
*/
void convertDispToDepth(double baseline);

/**
* @brief Reverses the order of the stereo sockets when creating CameraInfo to calculate Tx component of Projection matrix.
* By default the right socket is used as the base, calling this function will set left as base.
*/
void reverseStereoSocketOrder();

void toRosMsg(std::shared_ptr<dai::ImgFrame> inData, std::deque<ImageMsgs::Image>& outImageMsgs);
ImageMsgs::Image toRosMsgRawPtr(std::shared_ptr<dai::ImgFrame> inData, const sensor_msgs::msg::CameraInfo& info = sensor_msgs::msg::CameraInfo());
Expand Down Expand Up @@ -100,6 +115,8 @@ class ImageConverter {
bool _convertDispToDepth = false;
bool _addExpOffset = false;
dai::CameraExposureOffset _expOffset;
bool _reverseStereoSocketOrder = false;
double _baseline;
};

} // namespace ros
Expand Down
Loading
Loading