双目立体视觉(3)- ZED2 & ROS Melodic 发布RGB图像及深度信息

本文介绍如何在ROS环境中使用ZED2相机,并详细解释了ZED2 ROS Wrapper的配置参数及其作用,包括视频参数、深度参数、位置跟踪参数等。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

 

国际惯例:Src https://github.com/stereolabs/zed-examples

查看本人系列文章了解ZED2 SDK in Linux build(CUDA 10.0 used): https://blog.csdn.net/hhaowang/article/details/115401380?spm=1001.2014.3001.5501

ZED2官方文档:https://www.stereolabs.com/docs/


目录

1. 安装zed-ros-wrapper依赖

Build the program

编译zed_ros_wrapper包

简单测试:

2 ZED2 wrapper 话题列表

查看节点信息

查看话题信息

左相机发布话题列表

右相机话题

双目及深度话题

SLAM相关

传感器数据发布话题

3. ZED参数服务器

Parameters with prefix general

VIDEO PARAMETERS

DEPTH PARAMETERS

POSITION PARAMETERS

MAPPING PARAMETERS

SENSORS PARAMETERS (ONLY ZED-M AND ZED 2)

OBJECT DETECTION PARAMETERS (ONLY ZED 2)

Dynamic parameters

4.  ZED TF


1. 安装zed-ros-wrapper依赖

项目地址 https://github.com/stereolabs/zed-ros-wrapper#build-the-program

Build the program

The zed_ros_wrapper is a catkin package. It depends on the following ROS packages:

  • nav_msgs
  • tf2_geometry_msgs
  • message_runtime
  • catkin
  • roscpp
  • stereo_msgs
  • rosconsole
  • robot_state_publisher
  • urdf
  • sensor_msgs
  • image_transport
  • roslint
  • diagnostic_updater
  • dynamic_reconfigure
  • tf2_ros
  • message_generation
  • nodelet

编译zed_ros_wrapper包

$ cd ~/catkin_ws/src
$ git clone https://github.com/stereolabs/zed-ros-wrapper.git
$ cd ../
$ rosdep install --from-paths src --ignore-src -r -y
$ catkin_make -DCMAKE_BUILD_TYPE=Release
$ source ./devel/setup.bash

简单测试:

ZED2 camera:

$ roslaunch zed_wrapper zed2.launch

2 ZED2 wrapper 话题列表

查看节点信息

查看话题信息

左相机发布话题列表

rgb_image相关话题默认以左相机数据帧发布

右相机话题

双目及深度话题

SLAM相关

(暂不考虑)

传感器数据发布话题


3. ZED参数服务器

# params/zed2.yaml
# Parameters for Stereolabs ZED2 camera
---

general:
    camera_model:               'zed2'

depth:
    min_depth:                  0.7             # Min: 0.2, Max: 3.0 - Default 0.7 - Note: reducing this value wil require more computational power and GPU memory
    max_depth:                  20.0            # Max: 40.0

pos_tracking:
    imu_fusion:                 true            # enable/disable IMU fusion. When set to false, only the optical odometry will be used.

sensors:
    sensors_timestamp_sync:     false           # Synchronize Sensors messages timestamp with latest received frame
    publish_imu_tf:             true            # publish `IMU -> <cam_name>_left_camera_frame` TF

object_detection:
    od_enabled:                 false           # True to enable Object Detection [only ZED 2]
    model:                      0               # '0': MULTI_CLASS_BOX - '1': MULTI_CLASS_BOX_ACCURATE - '2': HUMAN_BODY_FAST - '3': HUMAN_BODY_ACCURATE
    confidence_threshold:       50              # Minimum value of the detection confidence of an object [0,100]
    max_range:                  15.             # Maximum detection range
    object_tracking_enabled:    true            # Enable/disable the tracking of the detected objects
    body_fitting:               false           # Enable/disable body fitting for 'HUMAN_BODY_FAST' and 'HUMAN_BODY_ACCURATE' models
    mc_people:                  true            # Enable/disable the detection of persons for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
    mc_vehicle:                 true            # Enable/disable the detection of vehicles for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
    mc_bag:                     true            # Enable/disable the detection of bags for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
    mc_animal:                  true            # Enable/disable the detection of animals for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
    mc_electronics:             true            # Enable/disable the detection of electronic devices for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
    mc_fruit_vegetable:         true            # Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models

Parameters with prefix general

PARAMETERDESCRIPTIONVALUE
camera_nameA custom name for the ZED camera. Used as namespace and prefix for camera TF framesstring, default=zed
camera_modelType of Stereolabs camerazed: ZED, zedm: ZED-M, zed2: ZED 2
camera_flipFlip the camera data if it is mounted upsidedowntrue, false
zed_idSelect a ZED camera by its ID. Useful when multiple cameras are connected. ID is ignored if an SVO path is specifiedint, default 0
serial_numberSelect a ZED camera by its serial numberint, default 0
resolutionSet ZED camera resolution0: HD2K, 1: HD1080, 2: HD720, 3: VGA
grab_frame_rateSet ZED camera grabbing framerateint
gpu_idSelect a GPU device for depth computationint, default -1 (best device found)
base_frameFrame_id of the frame that indicates the reference base of the robotstring, default=base_link
verboseEnable/disable the verbosity of the SDKtrue, false
svo_compressionSet SVO compression mode0: LOSSLESS (PNG/ZSTD), 1: H264 (AVCHD) ,2: H265 (HEVC)
self_calibEnable/disable self calibration at startingtrue, false

VIDEO PARAMETERS

Parameters with prefix video

PARAMETERDESCRIPTIONVALUE
img_downsample_factorResample factor for images [0.01,1.0]. The SDK works with native image sizes, but publishes rescaled image.double, default=1.0
extrinsic_in_camera_frameIf false extrinsic parameter in camera_info will use ROS native frame (X FORWARD, Z UP) instead of the camera frame (Z FORWARD, Y DOWN) [true use old behavior as for version < v3.1]true, false

DEPTH PARAMETERS

Parameters with prefix depth

PARAMETERDESCRIPTIONVALUE
qualitySelect depth map quality0: NONE, 1: PERFORMANCE, 2: MEDIUM, 3: QUALITY, 4: ULTRA
sensing_modeSelect depth sensing mode (change only for VR/AR applications)0: STANDARD, 1: FILL
depth_stabilizationEnable depth stabilization. Stabilizing the depth requires an additional computation load as it enables tracking0: disabled, 1: enabled
openni_depth_modeConvert 32bit depth in meters to 16bit in millimeters0: 32bit float meters, 1: 16bit uchar millimeters
depth/depth_downsample_factorResample factor for depth data matrices [0.01,1.0]. The SDK works with native data sizes, but publishes rescaled matrices (depth map, point cloud, …)double, default=1.0
min_depthMinimum value allowed for depth measuresMin: 0.3 (ZED) or 0.1 (ZED-M), Max: 3.0 - Note: reducing this value will require more computational power and GPU memory. In cases of limited compute power, increasing this value can provide better performance
max_depthMaximum value allowed for depth measuresMin: 1.0, Max: 30.0 - Values beyond this limit will be reported as TOO_FAR

POSITION PARAMETERS

Parameters with prefix pos_tracking

PARAMETERDESCRIPTIONVALUE
publish_tfEnable/disable publish TF framestrue, false
publish_map_tfEnable/disable publish map TF frametrue, false
map_frameFrame_id of the pose messagestring, default=map
odometry_frameFrame_id of the odom messagestring, default=odom
area_memory_db_pathPath of the database file for loop closure and relocalization that contains learnt visual information about the environmentstring, default=``
pose_smoothingEnable smooth pose correction for small drift correction0: disabled, 1: enabled
area_memoryEnable Loop Closingtrue, false
floor_alignmentIndicates if the floor must be used as origin for height measurestrue, false
initial_base_poseInitial reference posevector, default=[0.0,0.0,0.0, 0.0,0.0,0.0] -> [X, Y, Z, R, P, Y]
init_odom_with_first_valid_poseIndicates if the odometry must be initialized with the first valid pose received by the tracking algorithmtrue, false
path_pub_rateFrequency (Hz) of publishing of the trajectory messagesfloat, default=2.0
path_max_countMaximum number of poses kept in the pose arrays (-1 for infinite)int, default=-1

MAPPING PARAMETERS

Parameters with prefix mapping

Note: the mapping module requires SDK v2.8 or higher

PARAMETERDESCRIPTIONVALUE
mapping_enabledEnable/disable the mapping moduletrue, false
resolutionResolution of the fused point cloud [0.01, 0.2]double, default=0.1
max_mapping_rangeMaximum depth range while mapping in meters (-1 for automatic calculation) [2.0, 20.0]double, default=-1
fused_pointcloud_freqPublishing frequency (Hz) of the 3D map as fused point clouddouble, default=1.0

SENSORS PARAMETERS (ONLY ZED-M AND ZED 2)

Parameters with prefix sensors

PARAMETERDESCRIPTIONVALUE
sensors_timestamp_syncSynchronize Sensors message timestamp with latest received frametrue, false

OBJECT DETECTION PARAMETERS (ONLY ZED 2)

Parameters with prefix object_detection

PARAMETERDESCRIPTIONVALUE
od_enabledEnable/disable the Object Detection moduletrue, false
confidence_thresholdMinimum value of the detection confidence of an objectint [0,100]
object_tracking_enabledEnable/disable the tracking of the detected objectstrue, false
people_detectionEnable/disable the detection of personstrue, false
vehicle_detectionEnable/disable the detection of vehiclestrue, false

Dynamic parameters

The ZED node lets you reconfigure these parameters dynamically:

PARAMETERDESCRIPTIONVALUE
general/pub_frame_rateFrequency of the publishing of Video and Depth images (equal or minor to grab_frame_rate value)float [0.1,100.0]
depth/depth_confidenceThreshold to reject depth values based on their confidence. Each depth pixel has a corresponding confidence. A lower value means more confidence and precision (but less density). An upper value reduces filtering (more density, less certainty). A value of 100 will allow values from 0 to 100. (no filtering). A value of 90 will allow values from 10 to 100. (filtering lowest confidence values). A value of 30 will allow values from 70 to 100. (keeping highest confidence values and lowering the density of the depth map). The value should be in [1,100]. By default, the confidence threshold is set at 100, meaning that no depth pixel will be rejected.int [0,100]
depth/depth_texture_confThreshold to reject depth values based on their textureness confidence. A lower value means more confidence and precision (but less density). An upper value reduces filtering (more density, less certainty). The value should be in [1,100]. By default, the confidence threshold is set at 100, meaning that no depth pixel will be rejected.int [0,100]
depth/point_cloud_freqFrequency of the pointcloud publishing (equal or minor to frame_rate value)float [0.1,100.0]
video/brightnessDefines the brightness controlint [0,8]
video/contrastDefines the contrast controlint [0,8]
video/hueDefines the hue controlint [0,11]
video/saturationDefines the saturation controlint [0,8]
video/sharpnessDefines the sharpness controlint [0,8]
video/gammaDefines the gamma controlint [1,9]
video/auto_exposure_gainDefines if the Gain and Exposure are in automatic mode or nottrue, false
video/gainDefines the gain control [only if auto_exposure_gain is false]int [0,100]
video/exposureDefines the exposure control [only if auto_exposure_gain is false]int [0,100]
video/auto_whitebalanceDefines if the White balance is in automatic mode or nottrue, false
video/whitebalance_temperatureDefines the color temperature value (x100)int [42,65]

To modify a dynamic parameter, you can use the GUI provided by the rqt stack:

$ rosrun rqt_reconfigure rqt_reconfigure


4.  ZED TF


 

利用 ZED 相机为 rtabmap_ros 录制 rosbag 包的步骤如下: 1. 安装 ZED 相机驱动和 SDK。可以在官网上下载对应的安装包,然后按照官方文档进行安装。 2. 安装 rtabmap 和 rtabmap_ros。可以使用以下命令进行安装: ``` sudo apt-get install ros-&lt;distro&gt;-rtabmap ros-&lt;distro&gt;-rtabmap-ros ``` 其中, `&lt;distro&gt;` 表示 ROS 版本,比如 `melodic`。 3. 启动 ZED 相机节点。可以使用以下命令启动 ZED 相机节点: ``` roslaunch zed_wrapper zed.launch ``` 4. 启动 rtabmap_ros 节点。可以使用以下命令启动 rtabmap_ros 节点: ``` roslaunch rtabmap_ros rtabmap.launch rtabmap_args:=&quot;--delete_db_on_start&quot; depth_topic:=/zed/depth/depth_registered rgb_topic:=/zed/rgb/image_rect_color ``` 其中,`depth_topic` 和 `rgb_topic` 分别指定 ZED 相机发布深度图和彩色图的 ROS 话题。 5. 手动控制 ZED 相机采集数据,或者使用 ROS 工具录制 rosbag 包。可以使用以下命令录制 rosbag 包: ``` rosbag record -O data.bag /zed/depth/depth_registered /zed/rgb/image_rect_color /rtabmap/odom ``` 其中,`data.bag` 是保存的 rosbag 包的文件名,`/zed/depth/depth_registered` 和 `/zed/rgb/image_rect_color` 分别是 ZED 相机发布深度图和彩色图的 ROS 话题,`/rtabmap/odom` 是 rtabmap_ros 发布的位姿信息的 ROS 话题。 录制完成后,可以使用以下命令播放 rosbag 包并查看 rtabmap 工作效果: ``` rosbag play data.bag --pause roslaunch rtabmap_ros rtabmap.launch rtabmap_args:=&quot;--delete_db_on_start&quot; depth_topic:=/camera/depth/image_rect_raw rgb_topic:=/camera/color/image_raw localization:=true ``` `localization:=true` 表示在 rtabmap 工作时只进行定位,不进行建图。在播放 rosbag 包时,先暂停,然后使用 rtabmap_ros 启动节点,最后按下空格键开始播放 rosbag 包。
评论 21
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

Techblog of HaoWANG

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值