ROS 1接口

本章介绍如何在Ubuntu系统中安装和使用Mech-Eye SDK的ROS 1接口。

最新ROS 1接口仅与Mech-Eye SDK 2.3.4或以上版本互相兼容。如安装最新版Mech-Eye SDK后希望继续使用已有的ROS程序,请根据迁移指南修改ROS程序。

使用前提

使用Mech-Eye SDK的ROS 1接口,需先满足以下使用前提:

Mech-Eye SDK的ROS 1接口经测试与上述版本的ROS 1和Ubuntu系统兼容。本章提供的代码示例均源自上述版本。

安装依赖的软件库

Mech-Eye SDK的ROS 1接口依赖以下软件库:

  • OpenCV:3.0或以上

  • PCL:1.8或以上

在ROS Noetic Ninjemys安装完成后,请执行以下命令安装依赖的软件库:

sudo apt install libopencv-dev
sudo apt install ros-noetic-cv-bridge
sudo apt install libpcl-dev
sudo apt install ros-noetic-pcl-conversions
sudo apt install python3-colcon-common-extensions

克隆并构建接口

请执行以下步骤克隆并构建Mech-Eye SDK的ROS 1接口:

  1. 执行以下命令克隆ROS 1接口:

    mkdir -p ~/catkin_ws/src && cd ~/catkin_ws/src
    git clone https://github.com/MechMindRobotics/mecheye_ros_interface.git
  2. 执行以下命令配置环境:

    source /opt/ros/noetic/setup.bash
  3. 执行以下命令构建ROS 1接口:

    cd ~/catkin_ws
    catkin_make

使用接口

请执行以下步骤使用Mech-Eye SDK的ROS 1接口:

  1. (可选)根据需求修改~/catkin_ws/src/mecheye_ros_interface/launch/路径下start_camera launch文件(.launch)中的配置:

    • 自动保存获取的文件至本地:将save_file的值设置为true,获取的文件将自动保存至/tmp/路径下。

    • 通过指定IP地址连接特定的相机:

      1. camera_ip的值设置为该相机的IP地址。

      2. 修改~/catkin_ws/src/mecheye_ros_interface/src/路径下的MechMindCamera C++编程语言文件(.cpp):将if (!findAndConnect(camera))函数注释,并将其下的行取消注释。

        修改工作路径下的C++编程语言文件或MechMindCamera头文件(.h)后,需重新执行catkin_make命令。
  2. 打开终端,然后执行以下命令启动接口:

    source ~/catkin_ws/devel/setup.bash
    roslaunch mecheye_ros_interface start_camera.launch
  3. 根据提示输入待连接相机的编号(index),并按Enter键连接相机。

  4. 打开一个新的终端,然后执行以下命令调用服务。将service_name替换为服务名称,parameter_name替换为参数名称,parameter_value替换为需设置的参数值。

    服务列表中提供了各个服务的命令示例。
    source ~/catkin_ws/devel/setup.bash
    rosservice call [/service_name] "{parameter_name: parameter_value}"

话题列表

以下为Mech-Eye SDK的ROS 1接口提供的话题:

  • /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 1接口提供的服务及各服务的命令示例。

数据采集

  • capture_color_image:采集2D图。

    示例:

    rosservice call /capture_color_image
  • capture_depth_map:采集深度图。

    示例:

    rosservice call /capture_depth_map
  • capture_point_cloud:采集无纹理点云。

    示例:

    rosservice call /capture_point_cloud
  • capture_textured_point_cloud:采集纹理点云。

    示例:

    rosservice call /capture_textured_point_cloud
  • capture_stereo_color_images:采集两个2D相机的2D图像。

    该服务仅可用于以下型号:DEEP、LSR S、LSR L、LSR XL和PRO XS。

    示例:

    rosservice call /capture_stereo_color_images

参数组管理

  • get_all_user_sets:获取所有可用参数组的名称。

    示例:

    rosservice call /get_all_user_sets
  • get_current_user_set:获取当前选中的参数组的名称。

    示例:

    rosservice call /get_current_user_set
  • set_current_user_set:选择需使用的参数组。

    该服务有1个参数:

    • value(string):要选择的参数组的名称。

    示例:选择名为123的参数组。

    rosservice call /set_current_user_set "{value: '123'}"
    如参数组名称由纯数字组成,需将参数组名放至单引号之间。
  • add_user_set:添加1个新参数组。添加后该参数组将自动被选中。

    该服务有1个参数:

    • value(string):要添加的参数组的名称。

    示例:添加名为123的参数组。

    rosservice call /add_user_set "{value: '123'}"
    如参数组名称由纯数字组成,需将参数组名放至单引号之间。
  • delete_user_set:删除指定的参数组。

    该服务有1个参数:

    value(string):要删除的参数组的名称。

    示例:删除名为123的参数组。

    rosservice call /delete_user_set "{value: '123'}"
    如参数组名称由纯数字组成,需将参数组名放至单引号之间。

获取相机信息

device_info:获取当前连接的相机的信息。

可获取的信息包括:

  • 型号

  • 序列号

  • 硬件版本

  • 固件版本

  • IP地址

  • 子网掩码

  • IP地址分配方式

  • 端口号

示例:

rosservice call /device_info

调节相机参数

Mech-Eye SDK 2.3.4及以上版本按照参数的数据类型提供通用的方法,其ROS 1接口提供对应的服务。获取和调节相机参数值时,需调用与该相机参数的数据类型对应的服务,并将相机参数名作为服务的参数输入。相机参数的名称和数据类型可在Mech-Eye SDK安装路径中的头文件中查阅:/opt/mech-mind/mech-eye-sdk/include/area_scan_3d_camera/parameters/

共有以下参数数据类型:

  • _Int

  • _Float

  • _Bool

  • _Enum

  • _Roi

  • _Range

  • _FloatArray

  • get_int_parameter:获取指定的_Int类型相机参数的值。

    该服务有1个参数:

    • name(string):相机参数的名称。

    示例:获取Scan2DExpectedGrayValue参数的值。

    rosservice call /get_int_parameter "{name: Scan2DExpectedGrayValue}"
  • set_int_parameter:设置指定的_Int类型相机参数的值。

    该服务有2个参数:

    • name(string):相机参数的名称。

    • value(int):该相机参数的新参数值。

    示例:将Scan2DExpectedGrayValue参数的值设置为101。

    rosservice call /set_int_parameter "{name: Scan2DExpectedGrayValue, value: 101}"
  • get_float_parameter:获取指定的_Float类型相机参数的值。

    该服务有1个参数:

    • name(string):相机参数的名称。

    示例:获取Scan2DExposureTime参数的值。

    rosservice call /get_float_parameter "{name: Scan2DExposureTime}"
  • set_float_parameter:设置指定的_Float类型相机参数的值。

    该服务有2个参数:

    • name(string):相机参数的名称。

    • value(float):该相机参数的新参数值。

    示例:将Scan2DExposureTime参数的值设置为40.1。

    rosservice call /set_float_parameter "{name: Scan2DExposureTime, value: 40.1}"
  • get_bool_parameter:获取指定的_Bool类型相机参数的值。

    该服务有1个参数:

    • name(string):相机参数的名称。

    示例:获取Scan2DToneMappingEnable参数的值。

    rosservice call /get_bool_parameter "{name: Scan2DToneMappingEnable}"
  • set_bool_parameter:设置指定的_Bool类型相机参数的值。

    该服务有2个参数:

    • name(string):相机参数的名称。

    • value(bool):该相机参数的新参数值。

    示例:将Scan2DToneMappingEnable参数的值设置为True

    rosservice call /set_bool_parameter "{name: Scan2DToneMappingEnable, value: True}"
  • get_enum_parameter:获取指定的_Enum类型相机参数的值。

    该服务有1个参数:

    • name(string):相机参数的名称。

    示例:获取Scan2DExposureMode参数的值。

    rosservice call /get_enum_parameter "{name: Scan2DExposureMode}"
  • set_enum_parameter:设置指定的_Enum类型相机参数的值。

    该服务有2个参数:

    • name(string):相机参数的名称。

    • value(string):该相机参数的新参数值。

    示例:将Scan2DExposureMode参数的值设置为Timed

    rosservice call /set_enum_parameter "{name: Scan2DExposureMode, value: Timed}"
  • get_roi_parameter:获取指定的_Roi类型相机参数的值。

    该服务有1个参数:

    • name(string):相机参数的名称。

    示例:获取Scan2DROI参数的值。

    rosservice call /get_roi_parameter "{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)。

    rosservice call /set_roi_parameter "{name: Scan2DROI, x: 20, y: 20, width: 600, height: 800}"
  • get_range_parameter:获取指定的_Range类型相机参数的值。

    该服务有1个参数:

    • name(string):相机参数的名称。

    示例:获取DepthRange参数的值。

    rosservice call /get_range_parameter "{name: DepthRange}"
  • set_range_parameter:设置指定的_Range类型相机参数的值。

    该服务有3个参数:

    • name(string):相机参数的名称。

    • lower(int32):该相机参数范围的新最小值。

    • upper(int32):该相机参数范围的新最大值。

    示例:将DepthRange参数的值设置为200~1000

    rosservice call /set_range_parameter "{name: DepthRange, lower: 200, upper: 1000}"
  • get_float_array_parameter:获取指定的_FloatArray类型相机参数的值。

    该服务有1个参数:

    • name(string):相机参数的名称。

    示例:获取Scan2DHDRExposureSequence参数的值。

    rosservice call /get_float_array_parameter "{name: Scan2DHDRExposureSequence}"
  • set_float_array_parameter:设置指定的_FloatArray类型相机参数的值。

    该服务有2个参数:

    • name(string):相机参数的名称。

    • array(float64[]):该相机参数新参数值。

    示例:将Scan2DHDRExposureSequence参数的值设置为[30.0, 35.5, 40.0]

    rosservice call /set_float_array_parameter "{name: Scan2DHDRExposureSequence, array: [30.0,35.5,40.0]}"

我们重视您的隐私

我们使用 cookie 为您在我们的网站上提供最佳体验。继续使用该网站即表示您同意使用 cookie。如果您拒绝,将使用一个单独的 cookie 来确保您在访问本网站时不会被跟踪或记住。