ROS 1 Interface

This topic introduces how to install and use the ROS 1 interface for Mech-Eye SDK.

The latest ROS 1 interfaces are only compatible with Mech-Eye SDK 2.3.4 or above. If you wish to keep using the existing ROS program after installing the latest version of Mech-Eye SDK, please modify the ROS program according to Migration Guide.

Prerequisites

In order to use the ROS 1 interface of Mech-Eye SDK, the following prerequisites must be satisfied:

The ROS 1 interface of Mech-Eye SDK has been tested with the above versions of ROS 1 and the Ubuntu. The command examples in this topic are based on the above versions.

Install Dependent Software Libraries

The ROS 1 interface of Mech-Eye SDK depends on the following software libraries:

  • OpenCV: version 3.0 or above

  • PCL: version 1.8 or above

After installing ROS Noetic Ninjemys, execute the following commands to installed the dependent software libraries:

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

Clone and Build the Interface

Follow these steps to clone and build the ROS 1 interface for Mech-Eye SDK:

  1. Execute the following commands to clone the ROS 1 interface:

    mkdir -p ~/catkin_ws/src && cd ~/catkin_ws/src
    git clone https://github.com/MechMindRobotics/mecheye_ros_interface.git
  2. Execute the following command to set up the environment:

    source /opt/ros/noetic/setup.bash
  3. Execute the following commands to build the ROS 1 interface:

    cd ~/catkin_ws
    catkin_make

Use the Interface

Follow these steps to use the ROS 1 interface for Mech-Eye SDK:

  1. (Optional) Change the configurations in the start_camera launch file (.launch) in ~/catkin_ws/src/mecheye_ros_interface/launch/ according to your needs:

    • Automatically save the obtained files to local: Set the value of save_file to true to automatically save the obtained files to the /tmp/ directory.

    • Connect to a specific camera through the specified IP address:

      1. Set the value of camera_ip to the IP address of the camera.

      2. Modify the MechMindCamera C++ programming file (.cpp) in /catkin_ws/src/mecheye_ros_interface/src/: Comment the if (!findAndConnect(camera)) function, and uncomment the lines below this function.

        After modifying the C++ programming files or MechMindCamera header file (.h) in the working directory, execute the catkin_make command again.
  2. Open a terminal and execute the following command to start up the interface:

    source ~/catkin_ws/devel/setup.bash
    roslaunch mecheye_ros_interface start_camera.launch
  3. Input the index of the camera to which you want to connect according to the instruction, and press Enter to connect to the camera.

  4. Open a new terminal and execute the following command to invoke a service. Replace service_name with the name of the service, parameter_name with the name of the camera parameter, and parameter_value with the parameter value to be set.

    The Services section provides the example commands of each service.
    source ~/catkin_ws/devel/setup.bash
    rosservice call [/service_name] "{parameter_name: parameter_value}"

Topics

The following are the topics provided for the ROS 1 interface of Mech-Eye SDK:

  • /mechmind/camera_info: camera intrinsic parameters

  • /mechmind/stereo_color_image_left: the left stereo 2D image encoded as bgr8

  • /mechmind/stereo_color_image_left: the left stereo 2D image encoded as bgr8

  • /mechmind/stereo_color_image_right: the right stereo 2D image encoded as bgr8

  • /mechmind/depth_map: the depth map encoded as a single-channel image, the channel containing a 32-bit float number

  • /mechmind/point_cloud: the untextured point cloud data

  • /mechmind/textured_point_cloud: the textured point cloud data

Services

The following are the services provided by the ROS 1 interface of Mech-Eye SDK and the command example of each service.

Acquire Data

  • capture_color_image: Acquire the 2D image.

    Example:

    rosservice call /capture_color_image
  • capture_depth_map: Acquire the depth map.

    Example:

    rosservice call /capture_depth_map
  • capture_point_cloud: Acquire the untextured point cloud.

    Example:

    rosservice call /capture_point_cloud
  • capture_textured_point_cloud: Acquire the textured point cloud.

    Example:

    rosservice call /capture_textured_point_cloud
  • capture_stereo_color_images: Acquire the 2D images from both 2D cameras.

    This service is only available for the following models: DEEP, LSR S, LSR L, LSR XL, and PRO XS.

    Example:

    rosservice call /capture_stereo_color_images

Manage Parameter Groups

  • get_all_user_sets: Obtain the names of all available parameter groups.

    Example:

    rosservice call /get_all_user_sets
  • get_current_user_set: Obtain the name of the currently selected parameter group.

    Example:

    rosservice call /get_current_user_set
  • set_current_user_set: Select the parameter group to be used.

    This service has 1 parameter:

    • value (string): the name of the parameter group to be selected.

    Example: Select the parameter group named 123.

    rosservice call /set_current_user_set "{value: '123'}"
    Parameter group names that consist of numbers only must be surrounded by single quotation marks.
  • add_user_set: Add a parameter group. The newly added parameter group is automatically selected as the current parameter group.

    This service has 1 parameter:

    • value (string): the name of the parameter group to be added.

    Example: Add a parameter group named 123.

    rosservice call /add_user_set "{value: '123'}"
    Parameter group names that consist of numbers only must be surrounded by single quotation marks.
  • delete_user_set: Delete the specified parameter group.

    This service has 1 parameter:

    value (string): the name of the parameter group to be deleted.

    Example: Delete the parameter group named 123.

    rosservice call /delete_user_set "{value: '123'}"
    Parameter group names that consist of numbers only must be surrounded by single quotation marks.

Obtain Camera Information

device_info: Obtain the information of the currently connected camera.

The obtained information includes:

  • Model

  • Serial number

  • Hardware version

  • Firmware version

  • IP address

  • Subnet mask

  • IP address assignment method

  • Port number

Example:

rosservice call /device_info

Adjust Camera Parameters

Mech-Eye SDK 2.3.4 and above provide methods according to the data types of the camera parameters, and the ROS 1 interface provides the corresponding services. To obtain or adjust the value of a camera parameter, call the service corresponding to the data type of the camera parameter and input the name of the camera parameter as the service’s parameter. The data types and names of the camera parameters can be found in the header files in the installation path of Mech-Eye SDK: /opt/mech-mind/mech-eye-sdk/include/area_scan_3d_camera/parameters/.

The following data types of camera parameters are distinguished:

  • _Int

  • _Float

  • _Bool

  • _Enum

  • _Roi

  • _Range

  • _FloatArray

  • get_int_parameter: Obtain the value of the specified _Int-type camera parameter.

    This service has 1 parameter:

    • name (string): the name of the camera parameter.

    Example: Obtain the value of the Scan2DExpectedGrayValue parameter.

    rosservice call /get_int_parameter "{name: Scan2DExpectedGrayValue}"
  • set_int_parameter: Set the value of the specified _Int-type camera parameter.

    This service has 2 parameters:

    • name (string): the name of the camera parameter.

    • value (int): the new value of the camera parameter.

    Example: Set the value of the Scan2DExpectedGrayValue parameter to 101.

    rosservice call /set_int_parameter "{name: Scan2DExpectedGrayValue, value: 101}"
  • get_float_parameter: Obtain the value of the specified _Float-type camera parameter.

    This service has 1 parameter:

    • name (string): the name of the camera parameter.

    Example: Obtain the value of the Scan2DExposureTime parameter.

    rosservice call /get_float_parameter "{name: Scan2DExposureTime}"
  • set_float_parameter: Set the value of the specified _Float-type camera parameter.

    This service has 2 parameters:

    • name (string): the name of the camera parameter.

    • value (float): the new value of the camera parameter.

    Example: Set the value of the Scan2DExposureTime parameter to 40.1.

    rosservice call /set_float_parameter "{name: Scan2DExposureTime, value: 40.1}"
  • get_bool_parameter: Obtain the value of the specified _Bool-type camera parameter.

    This service has 1 parameter:

    • name (string): the name of the camera parameter.

    Example: Obtain the value of the Scan2DToneMappingEnable parameter.

    rosservice call /get_bool_parameter "{name: Scan2DToneMappingEnable}"
  • set_bool_parameter: Set the value of the specified _Bool-type camera parameter.

    This service has 2 parameters:

    • name (string): the name of the camera parameter.

    • value (bool): the new value of the camera parameter.

    Example: Set the value of the Scan2DToneMappingEnable parameter to True.

    rosservice call /set_bool_parameter "{name: Scan2DToneMappingEnable, value: True}"
  • get_enum_parameter: Obtain the value of the specified _Enum-type camera parameter.

    This service has 1 parameter:

    • name (string): the name of the camera parameter.

    Example: Obtain the value of the Scan2DExposureMode parameter.

    rosservice call /get_enum_parameter "{name: Scan2DExposureMode}"
  • set_enum_parameter: Set the value of the specified _Enum-type camera parameter.

    This service has 2 parameters:

    • name (string): the name of the camera parameter.

    • value (string): the new value of the camera parameter.

    Example: Set the value of the Scan2DExposureMode parameter to Timed.

    rosservice call /set_enum_parameter "{name: Scan2DExposureMode, value: Timed}"
  • get_roi_parameter: Obtain the value of the specified _Roi-type camera parameter.

    This service has 1 parameter:

    • name (string): the name of the camera parameter.

    Example: Obtain the value of the Scan2DROI parameter.

    rosservice call /get_roi_parameter "{name: Scan2DROI}"
  • set_roi_parameter: Set the value of the specified _Roi-type camera parameter.

    This service has 5 parameters:

    • name (string): the name of the camera parameter.

    • x (uint32): the new x-coordinate of the upper-left corner of the ROI.

    • y (uint32): the new y-coordinate of the upper-left corner of the ROI.

    • width (uint32): the new width of the ROI.

    • height (uint32): the new height of the ROI.

    Example: Set the value of the Scan2DROI parameter to 20, 20, 600, 800 (which is an ROI that is 600 px wide, 800 px high and has its upper-left corner at the (20,20) pixel).

    rosservice call /set_roi_parameter "{name: Scan2DROI, x: 20, y: 20, width: 600, height: 800}"
  • get_range_parameter: Obtain the value of the specified _Range-type camera parameter.

    This service has 1 parameter:

    • name (string): the name of the camera parameter.

    Example: Obtain the value of the DepthRange parameter.

    rosservice call /get_range_parameter "{name: DepthRange}"
  • set_range_parameter: Set the value of the specified _Range-type camera parameter.

    This service has 3 parameters:

    • name (string): the name of the camera parameter.

    • lower (int32): the new minimum value of the camera parameter’s value range.

    • upper (int32): the new maximum value of the camera parameter’s value range.

    Example: Set the value of the DepthRange parameter to 200–1000.

    rosservice call /set_range_parameter "{name: DepthRange, lower: 200, upper: 1000}"
  • get_float_array_parameter: Obtain the value of the specified _FloatArray-type camera parameter.

    This service has 1 parameter:

    • name (string): the name of the camera parameter.

    Example: Obtain the value of the Scan2DHDRExposureSequence parameter.

    rosservice call /get_float_array_parameter "{name: Scan2DHDRExposureSequence}"
  • set_float_array_parameter: Set the value of the specified _FloatArray-type camera parameter.

    This service has 2 parameters:

    • name (string): the name of the camera parameter.

    • array (float64[]): the new value of the camera parameter.

    Example: Set the value of the Scan2DHDRExposureSequence parameter to [30.0, 35.5, 40.0].

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

We Value Your Privacy

We use cookies to provide you with the best possible experience on our website. By continuing to use the site, you acknowledge that you agree to the use of cookies. If you decline, a single cookie will be used to ensure you're not tracked or remembered when you visit this website.