ROS 2接口
本章介绍如何在Ubuntu系统中安装和使用Mech-Eye SDK的ROS 2接口。
最新ROS 2接口仅与Mech-Eye SDK 2.3.4或以上版本互相兼容。如安装最新版Mech-Eye SDK后希望继续使用已有的ROS程序,请根据迁移指南修改ROS程序。 |
使用前提
使用Mech-Eye SDK的ROS 2接口,需先满足以下使用前提:
-
ROS 2版本:推荐使用稳定版本的ROS 2,即Humble Hawksbill。
-
Ubuntu版本:推荐使用22.04,即ROS Humble Hawksbill的主要目标平台。
Mech-Eye SDK的ROS 2接口经测试与上述版本的ROS 2和Ubuntu系统兼容。本章提供的代码示例均源自上述版本。 |
-
安装Mech-Eye SDK:详见Mech-Eye SDK安装指南(Ubuntu)。
-
安装接口依赖的软件库。
安装依赖的软件库
Mech-Eye SDK的ROS 2接口依赖以下软件库:
-
OpenCV:3.0或以上
-
PCL:1.8或以上
-
(如需使用
ros2 launch
命令)xterm:无版本要求使用 ros2 launch
命令可便捷地在RViz中可视化获取的点云数据,无需进行额外操作。
在ROS Humble Hawksbill安装完成后,请执行以下命令安装依赖的软件库:
sudo apt install libopencv-dev
sudo apt install ros-humble-cv-bridge
sudo apt install libpcl-dev
sudo apt install ros-humble-pcl-conversions
sudo apt install python3-colcon-common-extensions
克隆并构建接口
请执行以下步骤克隆并构建Mech-Eye SDK的ROS 2接口:
-
执行以下命令克隆ROS 2接口:
mkdir -p ~/colcon_ws/src && cd ~/colcon_ws/src git clone https://github.com/MechMindRobotics/mecheye_ros2_interface.git
-
执行以下命令配置环境:
-
如使用Debian packages安装的ROS 2:
# Replace ".bash" with your shell if you're not using bash # Possible values are: setup.bash, setup.sh, setup.zsh source /opt/ros/humble/setup.bash
-
如从源构建的ROS 2:
# Replace ".bash" with your shell if you're not using bash # Possible values are: setup.bash, setup.sh, setup.zsh . ~/ros2_humble/install/local_setup.bash
-
-
执行以下命令构建ROS 2接口:
cd ~/colcon_ws colcon build
使用接口
请执行以下步骤使用Mech-Eye SDK的ROS 2接口:
-
(可选)根据需求修改~/colcon_ws/src/mecheye_ros2_interface/src/路径下MechMindCamera C++编程语言文件(.cpp)中的配置:
-
自动保存获取的文件至本地:将
save_file
的值设置为true
,获取的文件将自动保存至/tmp/路径下。 -
通过指定IP地址连接特定的相机:
-
将
camera_ip
的值设置为该相机的IP地址。 -
将
if (!findAndConnect(camera))
函数注释,并将其下的行取消注释。
-
-
转换坐标系:修改
fx
、fy
、u
和v
的值,将相机坐标系转换为其他坐标系。需用四元数表示旋转量。修改工作路径下的C++编程语言文件或MechMindCamera头文件(.h)后,需重新执行 colcon build
命令。
-
-
打开终端,然后执行以下命令启动接口:
-
使用
ros2 launch
命令:source ~/colcon_ws/install/setup.bash ros2 launch ~/colcon_ws/src/mecheye_ros2_interface/launch/start_camera.py
-
使用
ros2 run
命令:source ~/colcon_ws/install/setup.bash ros2 run mecheye_ros_interface start
-
-
根据提示输入待连接相机的编号(index),并按Enter键连接相机。
-
打开一个新的终端,然后执行以下命令调用服务。将service_name替换为服务名称,将ServiceName替换为服务文件名称,parameter_name替换为参数名称,parameter_value替换为需设置的参数值。
服务列表中提供了各个服务的命令示例。 source ~/colcon_ws/install/setup.bash ros2 service call [/service_name] [mecheye_ros_interface/srv/ServiceName] "{parameter_name: parameter_value}"
话题列表
以下为Mech-Eye SDK的ROS 2接口提供的话题:
-
/mechmind/camera_info:相机内参
-
/mechmind/color_image:编码格式为bgr8的2D图
-
/mechmind/stereo_color_image_left:编码格式为bgr8的左相机2D图
-
/mechmind/stereo_color_image_right:编码格式为bgr8的右相机2D图
-
/mechmind/depth_map:编码为32位浮点数单通道图像的深度图
-
/mechmind/point_cloud:无纹理点云数据
-
/mechmind/textured_point_cloud:纹理点云数据
服务列表
以下为Mech-Eye SDK的ROS 2接口提供的服务及各服务的命令示例。
数据采集
-
capture_color_image:采集2D图。
示例:
ros2 service call /capture_color_image mecheye_ros_interface/srv/CaptureColorImage
-
capture_depth_map:采集深度图。
示例:
ros2 service call /capture_depth_map mecheye_ros_interface/srv/CaptureDepthMap
-
capture_point_cloud:采集无纹理点云。
示例:
ros2 service call /capture_point_cloud mecheye_ros_interface/srv/CapturePointCloud
-
capture_textured_point_cloud:采集纹理点云。
示例:
ros2 service call /capture_textured_point_cloud mecheye_ros_interface/srv/CaptureTexturedPointCloud
-
capture_stereo_color_images:采集两个2D相机的2D图像。
该服务仅可用于以下型号:DEEP、LSR S、LSR L、LSR XL和PRO XS。 示例:
ros2 service call /capture_stereo_color_images mecheye_ros_interface/srv/CaptureStereoColorImages
参数组管理
-
get_all_user_sets:获取所有可用参数组的名称。
示例:
ros2 service call /get_all_user_sets mecheye_ros_interface/srv/GetAllUserSets
-
get_current_user_set:获取当前选中的参数组的名称。
示例:
ros2 service call /get_current_user_set mecheye_ros_interface/srv/GetCurrentUserSet
-
set_current_user_set:选择需使用的参数组。
该服务有1个参数:
-
value
(string):要选择的参数组的名称。
示例:选择名为123的参数组。
ros2 service call /set_current_user_set mecheye_ros_interface/srv/SetCurrentUserSet "{value: '123'}"
如参数组名称由纯数字组成,需将参数组名放至单引号之间。 -
-
add_user_set:添加1个新参数组。添加后该参数组将自动被选中。
该服务有1个参数:
-
value
(string):要添加的参数组的名称。
示例:添加名为123的参数组。
ros2 service call /add_user_set mecheye_ros_interface/srv/AddUserSet "{value: '123'}"
如参数组名称由纯数字组成,需将参数组名放至单引号之间。 -
-
delete_user_set:删除指定的参数组。
该服务有1个参数:
value
(string):要删除的参数组的名称。示例:删除名为123的参数组。
ros2 service call /delete_user_set mecheye_ros_interface/srv/DeleteUserSet "{value: '123'}"
如参数组名称由纯数字组成,需将参数组名放至单引号之间。
获取相机信息
device_info:获取当前连接的相机的信息。
可获取的信息包括:
-
型号
-
序列号
-
硬件版本
-
固件版本
-
IP地址
-
子网掩码
-
IP地址分配方式
-
端口号
示例:
ros2 service call /device_info mecheye_ros_interface/srv/DeviceInfo
调节相机参数
Mech-Eye SDK 2.3.4及以上版本按照参数的数据类型提供通用的方法,其ROS 2接口提供对应的服务。获取和调节相机参数值时,需调用与该相机参数的数据类型对应的服务,并将相机参数名作为服务的参数输入。相机参数的名称和数据类型可在Mech-Eye SDK安装路径中的头文件中查阅:/opt/mech-mind/mech-eye-sdk/include/area_scan_3d_camera/parameters/。 共有以下参数数据类型:
|
-
get_int_parameter:获取指定的_Int类型相机参数的值。
该服务有1个参数:
-
name
(string):相机参数的名称。
示例:获取Scan2DExpectedGrayValue参数的值。
ros2 service call /get_int_parameter mecheye_ros_interface/srv/GetIntParameter "{name: Scan2DExpectedGrayValue}"
-
-
set_int_parameter:设置指定的_Int类型相机参数的值。
该服务有2个参数:
-
name
(string):相机参数的名称。 -
value
(int):该相机参数的新参数值。
示例:将Scan2DExpectedGrayValue参数的值设置为101。
ros2 service call /set_int_parameter mecheye_ros_interface/srv/SetIntParameter "{name: Scan2DExpectedGrayValue, value: 101}"
-
-
get_float_parameter:获取指定的_Float类型相机参数的值。
该服务有1个参数:
-
name
(string):相机参数的名称。
示例:获取Scan2DExposureTime参数的值。
ros2 service call /get_float_parameter mecheye_ros_interface/srv/GetFloatParameter "{name: Scan2DExposureTime}"
-
-
set_float_parameter:设置指定的_Float类型相机参数的值。
该服务有2个参数:
-
name
(string):相机参数的名称。 -
value
(float):该相机参数的新参数值。
示例:将Scan2DExposureTime参数的值设置为40.1。
ros2 service call /set_float_parameter mecheye_ros_interface/srv/SetFloatParameter "{name: Scan2DExposureTime, value: 40.1}"
-
-
get_bool_parameter:获取指定的_Bool类型相机参数的值。
该服务有1个参数:
-
name
(string):相机参数的名称。
示例:获取Scan2DToneMappingEnable参数的值。
ros2 service call /get_bool_parameter mecheye_ros_interface/srv/GetBoolParameter"{name: Scan2DToneMappingEnable}"
-
-
set_bool_parameter:设置指定的_Bool类型相机参数的值。
该服务有2个参数:
-
name
(string):相机参数的名称。 -
value
(bool):该相机参数的新参数值。
示例:将Scan2DToneMappingEnable参数的值设置为True。
ros2 service call /set_bool_parameter mecheye_ros_interface/srv/SetBoolParameter "{name: Scan2DToneMappingEnable, value: True}"
-
-
get_enum_parameter:获取指定的_Enum类型相机参数的值。
该服务有1个参数:
-
name
(string):相机参数的名称。
示例:获取Scan2DExposureMode参数的值。
ros2 service call /get_enum_parameter mecheye_ros_interface/srv/GetEnumParameter "{name: Scan2DExposureMode}"
-
-
set_enum_parameter:设置指定的_Enum类型相机参数的值。
该服务有2个参数:
-
name
(string):相机参数的名称。 -
value
(string):该相机参数的新参数值。
示例:将Scan2DExposureMode参数的值设置为Timed。
ros2 service call /set_enum_parameter mecheye_ros_interface/srv/SetEnumParameter "{name: Scan2DExposureMode, value: Timed}"
-
-
get_roi_parameter:获取指定的_Roi类型相机参数的值。
该服务有1个参数:
-
name
(string):相机参数的名称。
示例:获取Scan2DROI参数的值。
ros2 service call /get_roi_parameter mecheye_ros_interface/srv/GetROIParameter "{name: Scan2DROI}"
-
-
set_roi_parameter:设置指定的_Roi类型相机参数的值。
该服务有5个参数:
-
name
(string):相机参数的名称。 -
x
(uint32):ROI的新左上角x坐标。 -
y
(uint32):ROI的新左上角y坐标。 -
width
(uint32):ROI的新宽度。 -
height
(uint32):ROI的新高度。
示例:将Scan2DROI参数的值设置为20, 20, 600, 800(即一个600px宽、800px高、左上角位于(20,20)的ROI)。
ros2 service call /set_roi_parameter mecheye_ros_interface/srv/SetROIParameter "{name: Scan2DROI, x: 20, y: 20, width: 600, height: 800}"
-
-
get_range_parameter:获取指定的_Range类型相机参数的值。
该服务有1个参数:
-
name
(string):相机参数的名称。
示例:获取DepthRange参数的值。
ros2 service call /get_range_parameter mecheye_ros_interface/srv/GetRangeParameter "{name: DepthRange}"
-
-
set_range_parameter:设置指定的_Range类型相机参数的值。
该服务有3个参数:
-
name
(string):相机参数的名称。 -
lower
(int32):该相机参数范围的新最小值。 -
upper
(int32):该相机参数范围的新最大值。
示例:将DepthRange参数的值设置为200~1000。
ros2 service call /set_range_parameter mecheye_ros_interface/srv/SetRangeParameter "{name: DepthRange, lower: 200, upper: 1000}"
-
-
get_float_array_parameter:获取指定的_FloatArray类型相机参数的值。
该服务有1个参数:
-
name
(string):相机参数的名称。
示例:获取Scan2DHDRExposureSequence参数的值。
ros2 service call /get_float_array_parameter mecheye_ros_interface/srv/GetFloatArrayParameter "{name: Scan2DHDRExposureSequence}"
-
-
set_float_array_parameter:设置指定的_FloatArray类型相机参数的值。
该服务有2个参数:
-
name
(string):相机参数的名称。 -
array
(float64[]):该相机参数新参数值。
示例:将Scan2DHDRExposureSequence参数的值设置为[30.0, 35.5, 40.0]。
ros2 service call /set_float_array_parameter mecheye_ros_interface/srv/SetFloatArrayParameter "{name: Scan2DHDRExposureSequence, array: [30.0,35.5,40.0]}"
-