OrbbecSDK ROS2 is a wrapper for the Orbbec 3D camera that provides seamless integration with the ROS2 environment. It supports ROS2 Foxy, Galactic, and Humble distributions.
Install ROS2
- Please refer to the official ROS 2 installation guide guidance
If your ROS2 command does not auto-complete, put the following two lines into your
.bashrc
or.zshrc
eval "$(register-python-argcomplete3 ros2)"
eval "$(register-python-argcomplete3 colcon)"
Create colcon
workspace
mkdir -p ~/ros2_ws/src
Get source code
cd ~/ros2_ws/src
git clone https://github.com/OrbbecDeveloper/OrbbecSDK_ROS2.git
Install deb dependencies
# assume you have sourced ROS environment, same blow
sudo apt install libgflags-dev nlohmann-json3-dev libgoogle-glog-dev \
ros-$ROS_DISTRO-image-transport ros-$ROS_DISTRO-image-publisher ros-$ROS_DISTRO-camera-info-manager
Install udev rules.
cd ~/ros2_ws/src/OrbbecSDK_ROS2/orbbec_camera/scripts
sudo bash install_udev_rules.sh
sudo udevadm control --reload-rules && sudo udevadm trigger
cd ~/ros2_ws/
# build release, Default is Debug
colcon build --event-handlers console_direct+ --cmake-args -DCMAKE_BUILD_TYPE=Release
Launch camera node
- On terminal 1
. ./install/setup.bash
ros2 launch orbbec_camera astra.launch.xml
- On terminal 2
. ./install/setup.bash
rviz2
Select the topic you want to display
- List topics / services/ parameters ( on terminal 3)
ros2 topic list
ros2 service list
ros2 param list
- Get device info
ros2 service call /camera/get_device_info orbbec_camera_msgs/srv/GetDeviceInfo '{}'
- Get SDK version
ros2 service call /camera/get_sdk_version orbbec_camera_msgs/srv/GetString '{}'
- Get exposure
ros2 service call /camera/get_color_exposure orbbec_camera_msgs/srv/GetInt32 '{}'
If your check
ir
ordepth
, please change/camera/get_color_exposure
to/camera/get_ir_exposure
or/camera/get_depth_exposure
, Same below.
- Get gain
ros2 service call /camera/get_color_gain orbbec_camera_msgs/srv/GetInt32 '{}'
- Get white balance
ros2 service call /camera/get_white_balance orbbec_camera_msgs/srv/GetInt32 '{}'
- Set auto exposure
ros2 service call /camera/set_color_auto_exposure std_srvs/srv/SetBool '{data: false}'
- Set white balance
ros2 service call /camera/set_white_balance orbbec_camera_msgs/srv/SetInt32 '{data: 4600}'
- Set laser enable
ros2 service call /camera/set_laser_enable std_srvs/srv/SetBool "{data: true}"
- toggle sensor
ros2 service call /camera/toggle_ir std_srvs/srv/SetBool "{data : true}"
The name of the following service already expresses its function.
However, it should be noted that the corresponding set_[ir|depth|color]*
and get[ir|depth|color]*
services are only available if you set enable[ir|depth|color]
to true
in the stream that corresponds to the argument of the launch file.
/camera/get_auto_white_balance
/camera/get_color_exposure
/camera/get_color_gain
/camera/get_depth_exposure
/camera/get_depth_gain
/camera/get_device_info
/camera/get_ir_exposure
/camera/get_ir_gain
/camera/get_ldp_status
/camera/get_sdk_version
/camera/get_white_balance
/camera/set_auto_white_balance
/camera/set_color_auto_exposure
/camera/set_color_exposure
/camera/set_color_gain
/camera/set_depth_auto_exposure
/camera/set_depth_exposure
/camera/set_depth_gain
/camera/set_fan_work_mode
/camera/set_floor_enable
/camera/set_ir_auto_exposure
/camera/set_ir_exposure
/camera/set_ir_gain
/camera/set_laser_enable
/camera/set_ldp_enable
/camera/set_white_balance
/camera/toggle_color
/camera/toggle_depth
/camera/toggle_ir
/camera/color/camera_info
: The color camera info./camera/color/image_raw
: The color stream image./camera/depth/camera_info
: The depth stream image./camera/depth/image_raw
: The depth stream image/camera/depth/points
: The point cloud, only available whenenable_point_cloud
istrue
./camera/depth_registered/points
: The colored point cloud, only available whenenable_colored_point_cloud
istrue
./camera/ir/camera_info
: The IR camera info./camera/ir/image_raw
: The IR stream image
- To get the
usb_port
of the camera, plug in the camera and run the following command in the terminal:
ros2 run orbbec_camera list_devices_node
- Set the
device_num
parameter to the number of cameras you have. - Go to the
OrbbecSDK_ROS2/launch/multi_xxx.launch.xml
file and change theusb_port
. - Don't forget to put the
include
tag inside thegroup
tag. Otherwise, the parameter values of different cameras may become contaminated.
<launch>
<!-- unique camera name-->
<arg name="camera_name" default="camera"/>
<!-- Hardware depth registration -->
<arg name="3d_sensor" default="astra_mini"/>
<!-- stereo_s_u3, astrapro, astra -->
<arg name="camera1_prefix" default="01"/>
<arg name="camera2_prefix" default="02"/>
<!-- TODO: change to your usb port -->
<arg name="camera1_usb_port" default="1-4.2.1"/>
<arg name="camera2_usb_port" default="1-4.2.1"/>
<arg name="device_num" default="2"/>
<node name="camera" pkg="orbbec_camera" exec="ob_cleanup_shm_node" output="screen"/>
<group>
<include file="$(find-pkg-share orbbec_camera)/launch/gemini2.launch.xml">
<arg name="camera_name" value="camera_$(var camera1_prefix)"/>
<arg name="usb_port" value="$(var camera1_usb_port)"/>
<arg name="device_num" value="$(var device_num)"/>
</include>
</group>
<group>
<include file="$(find-pkg-share orbbec_camera)/launch/dabai_dcw.launch.xml">
<arg name="camera_name" value="camera_$(var camera2_prefix)"/>
<arg name="usb_port" value="$(var camera2_usb_port)"/>
<arg name="device_num" value="$(var device_num)"/>
</include>
</group>
<node pkg="tf2_ros" exec="static_transform_publisher" name="camera_tf"
args="0 0 0 0 0 0 camera01_link camera02_link"/>
</launch>
- Note that the astra camera uses semaphores for process synchronization.
If the camera start fails, the semaphore file may be left in
/dev/shm
, causing the next start to become stuck. To avoid this, run the following command before launching:
ros2 run orbbec_camera ob_cleanup_shm_node
This will clean up /dev/shm/
.
- To launch the cameras, run the following command:
ros2 launch orbbec_camera multi_camera.launch.xml
The following are the launch parameters available:
connection_delay
: The delay time in milliseconds for reopening the device. Some devices, such as Astra mini, require a longer time to initialize and reopening the device immediately can cause firmware crashes when hot plugging.enable_point_cloud
: Enables the point cloud.enable_colored_point_cloud
: Enables the RGB point cloud.point_cloud_qos
,[color|depth|ir]_qos,``[color|depth|ir]_camera_info_qos
: ROS2 Message Quality of Service (QoS) settings. The possible values areSYSTEM_DEFAULT
,DEFAULT
,PARAMETER_EVENTS
,SERVICES_DEFAULT
,PARAMETERS
,SENSOR_DATA
and are case-insensitive. These correspond tormw_qos_profile_system_default
,rmw_qos_profile_default
,rmw_qos_profile_parameter_events
,rmw_qos_profile_services_default
,rmw_qos_profile_parameters
, andSENSOR_DATA
, respectively.enable_d2c_viewer
: Publishes the D2C overlay image (for testing only).device_num
: The number of devices. This must be filled in if multiple cameras are required.color_width
,color_height
,color_fps
: The resolution and frame rate of the color stream.ir_width
,ir_height
,ir_fps
: The resolution and frame rate of the IR stream.depth_width
,depth_height
,depth_fps
: The resolution and frame rate of the depth stream.enable_color
: Enables the RGB camera.enable_depth
: Enables the depth camera.enable_ir
: Enables the IR camera.depth_registration
: Enables hardware alignment the depth frame to color frame. This field is required when theenable_colored_point_cloud
is set totrue
.usb_port
: The USB port of the camera. This is required when multiple cameras are used.enable_accel
: Enables the accelerometer.accel_rate
: The frequency of the accelerometer, the optional values are1.5625hz
,3.125hz
,6.25hz
,12.5hz
,25hz
,50hz
,100hz
,200hz
,500hz
,1khz
,2khz
,4khz
,8khz
,16khz
,32khz
. The specific value depends on the current camera.accel_range
: The range of the accelerometer, the optional values are2g
,4g
,8g
,16g
. The specific value depends on the current camera.enable_gyro
: Whether to enable the gyroscope.gyro_rate
: The frequency of the gyroscope, the optional values are1.5625hz
,3.125hz
,6.25hz
,12.5hz
,25hz
,50hz
,100hz
,200hz
,500hz
,1khz
,2khz
,4khz
,8khz
,16khz
,32khz
. The specific value depends on the current camera.gyro_range
: The range of the gyroscope, the optional values are16dps
,31dps
,62dps
,125dps
,250dps
,500dps
,1000dps
,2000dps
. The specific value depends on the current camera.
ros2 run orbbec_camera list_camera_profile_mode_node
product serials | launch file |
---|---|
astra+ | astra_adv.launch.xml |
astra | astra.launch.xml |
astra2 | astra2.launch.xml |
astra mini | astra_mini.launch.xml |
astra mini pro | astra_mini_pro.launch.xml |
astra pro | astra_pro.launch.xml |
astra stereo s | stereo_s_u3.launch.xml |
dabai | dabai.launch.xml |
dabai d1 | dabai_d1.launch.xml |
dabai dcw | dabai_dcw.launch.xml |
dabai dw | dabai_dw.launch.xml |
dabai pro | dabai_pro.launch.xml |
deeya | deeya.launch.xml |
femto | femto.launch.xml |
femto mega | femto_mega.launch.xml |
femto w | femto_w.launch.xml |
gemini | gemini.launch.xml |
gemini | gemini.launch.xml |
gemini2 / dabai DCL | gemini2.launch.xml |
gemini2L | gemini2L.launch.xml |
gemini e | gemini_e.launch.xml |
gemini e lite | gemini_e_lite.launch.xml |
Actually, All launch files all most the same, the only difference is the default value of the parameters.
If you need to use python launch file, please refer to gemini2.launch.py
.
SDK version | products list | firmware version |
---|---|---|
v1.6.2 | Astra2 | 2.8.20 |
Gemini2 L | 1.4.32 | |
Gemini2 | 1.4.60 | |
FemtoMega | 1.1.7 | |
Astra+ | 1.0.22/1.0.21/1.0.20/1.0.19 | |
Femto | 1.6.7 | |
Femto W | 1.1.8 | |
Dabai | 2436 | |
Dabai DCW | 2460 | |
Dabai DW | 2606 | |
Astra Mini Pro | 1007 | |
Astra Pro Plus | 2513 | |
A1 Pro | 3057 | |
Gemini E | 3460 | |
Gemini E Lite | 3606 | |
Gemini | 3.0.18 | |
v1.5.7 | Gemini2 | 1.4.60 |
FemtoMega | 1.1.5 | |
Astra+ | 1.0.22/1.0.21/1.0.20/1.0.19 | |
Femto | 1.6.7 | |
Femto W | 1.1.8 | |
Dabai | 2436 | |
Dabai DCW | 2460 | |
Dabai DW | 2606 | |
Astra Mini Pro | 1007 | |
Astra Pro Plus | 2513 | |
A1 Pro | 3057 | |
Gemini E | 3460 | |
Gemini E Lite | 3606 | |
Gemini | 3.0.18 | |
v1.4.3 | Astra+ | 1.0.22/1.0.21/1.0.20/1.0.19 |
Femto | 1.6.7 | |
*Femto W | 1.1.3 | |
Dabai | 2436 | |
Dabai DCW | 2460 | |
Dabai DW | 2606 | |
Astra Mini Pro | 1007 | |
Astra Pro Plus | 2513 | |
Gemini | 3.0.18 | |
v1.3.1 | Astra+ | 1.0.21/1.0.20/1.0.19 |
Femto | 1.6.7 | |
v1.2.8 | Astra+ | 1.0.20 |
Femto | 1.6.7 | |
v1.1.6 | Astra+ | 1.0.20/1.0.19 |
*Femto | 1.5.1 | |
v1.0.2 | Astra+ | 1.0.19 |
The default DDS settings (Galactic) may not be optimal for data transmission. Different DDS settings can have varying performance. In this example, we use CycloneDDS. For more detailed information, please refer to the ROS DDS Tuning。
● Edit cyclonedds configuration file
sudo gedit /etc/cyclonedds/config.xml
Add
<?xml version="1.0" encoding="UTF-8"?>
<CycloneDDS xmlns="https://cdds.io/config" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="https://cdds.io/confighttps://raw.githubusercontent.com/eclipse-cyclonedds/cyclonedds/master/etc/cyclonedds.xsd">
<Domain id="any">
<General>
<NetworkInterfaceAddress>lo</NetworkInterfaceAddress>
<AllowMulticast>false</AllowMulticast>
</General>
<Internal>
<MinimumSocketReceiveBufferSize>16MB</MinimumSocketReceiveBufferSize>
</Internal>
<Discovery>
<ParticipantIndex>auto</ParticipantIndex>
<MaxAutoParticipantIndex>30</MaxAutoParticipantIndex>
<Peers>
<Peer address="localhost"/>
</Peers>
</Discovery>
</Domain>
</CycloneDDS>
● Set the environment variables, add to .zshrc
or .bashrc
export ROS_DOMAIN_ID=42 # Numbers from 0 to 232
export ROS_LOCALHOST_ONLY=1
export CYCLONEDDS_URI=file:///etc/cyclonedds/config.xml
Tip:to understand why the maximum ROS_DOMAIN_ID is 232, please visit The ROS DOMAIN ID ● Increase UDP receive buffer size Edit
/etc/sysctl.d/10-cyclone-max.conf
Add
net.core.rmem_max=2147483647
net.core.rmem_default=2147483647
No Picture from Multiple Cameras
-
it's possible that the power supply is insufficient. To avoid this, do not connect all cameras to the same hub and use a powered hub instead.
-
It's also possible that the resolution is too high. To resolve this, try lowering the resolution.
Why are there so many launch files here
- The reason for the presence of multiple launch files is due to the fact that the default resolutions and image formats of different cameras vary. To make it easier to use, the launch files have been separated for each camera.
Copyright 2023 Orbbec Ltd.
Licensed under the Apache License, Version 2.0 (the "License"); you may not use this project except in compliance with the License. You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an " AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
Other names and brands may be claimed as the property of others