ROS 2 Bridge

For ROS 2 users to easily work with RDK, the APIs of RDK are wrapped into ROS packages in the [flexiv_ros2] repository. Key functionalities like joint torque and position control are supported, and the integration with ros2_control framework and MoveIt! 2 is also implemented.

Compatibility

Supported OS

Supported ROS 2 distribution

Ubuntu 20.04

Foxy Fitzroy

Ubuntu 22.04

Humble Hawksbill

Overview

flexiv_ros2 contains the following packages:

Package

Description

flexiv_bringup

Launch and run-time configurations for controllers and demos.

flexiv_controllers

Implementation of custom controllers.

flexiv_description

Robot URDF and mesh files.

flexiv_gripper

Implementation of the action server for Flexiv gripper control.

flexiv_hardware

Hardware interface between Flexiv robots and ros2_control framework.

flexiv_moveit_config

MoveIt configuration for Flexiv robots.

flexiv_msgs

Definition of messages used in RDK.

flexiv_test_nodes

Demo nodes and examples.

More details can be found in section Packages.

Environment setup

Note

The following instructions are for ROS 2 Humble. For ROS 2 Foxy, please replace foxy with humble in the commands, and clone the foxy branch of [flexiv_ros2].

  1. Install ROS 2 Humble via Debian Packages (ros-humble-desktop)

  2. Install additional packages:

    sudo apt install -y \
    python3-colcon-common-extensions \
    python3-rosdep2 \
    libeigen3-dev \
    ros-humble-xacro \
    ros-humble-tinyxml2-vendor \
    ros-humble-ros2-control \
    ros-humble-realtime-tools \
    ros-humble-control-toolbox \
    ros-humble-moveit \
    ros-humble-ros2-controllers \
    ros-humble-test-msgs \
    ros-humble-joint-state-publisher \
    ros-humble-joint-state-publisher-gui \
    ros-humble-robot-state-publisher \
    ros-humble-rviz2
    
  3. Create a ROS 2 workspace and clone flexiv_ros2:

    mkdir -p ~/flexiv_ros2_ws/src
    cd ~/flexiv_ros2_ws/src
    git clone https://github.com/flexivrobotics/flexiv_ros2.git
    cd flexiv_ros2/
    git submodule update --init --recursive
    
  4. Install dependencies:

    cd ~/flexiv_ros2_ws
    rosdep update
    rosdep install --from-paths src --ignore-src --rosdistro humble -r -y
    
  5. Compile flexiv_rdk library and install to the ~/rdk_install directory:

    cd ~/flexiv_ros2_ws/src/flexiv_ros2/flexiv_hardware/rdk/thirdparty
    bash build_and_install_dependencies.sh ~/rdk_install
    cd ~/flexiv_ros2_ws/src/flexiv_ros2/flexiv_hardware/rdk
    mkdir build && cd build
    cmake .. -DCMAKE_INSTALL_PREFIX=~/rdk_install
    cmake --build . --target install --config Release
    
  6. Build and source the workspace:

    cd ~/flexiv_ros2_ws
    source /opt/ros/humble/setup.bash
    colcon build --symlink-install --cmake-args -DCMAKE_PREFIX_PATH=~/rdk_install
    source install/setup.bash
    

Important

Whenever a new Terminal is opened, the ROS 2 Humble environment and flexiv_ros2 workspace must be sourced before running any ROS 2 commands:

source /opt/ros/humble/setup.bash
source ~/flexiv_ros2_ws/install/setup.bash

Packages

Below are detailed descriptions of all available packages, whose structure is based on that of ros2_control_demos.

flexiv_bringup

This package contains launch files: the main driver launcher, the MoveIt launch file and demo examples. To run the main launcher:

ros2 launch flexiv_bringup rizon.launch.py robot_sn:=[robot_sn]

Note

The required arguments for the launch file is:
  • robot_sn: the serial number of the robot. Remove any space, for example: Rizon4s-123456

To show all available arguments, run ros2 launch flexiv_bringup rizon.launch.py --show-args.

It will establish connection with the robot server, load the default rizon_arm_controller, and visualize the robot in RViZ. This controller uses position_command_interface, and will put the robot into joint position mode.

Note

The default Flexiv RDK control mode for ROS 2 joint position and velocity interfaces is the NRT_JOINT_POSITION.

Setting the rdk_control_mode to joint_impedance enables the user to run the joint position control in ROS 2 with Flexiv built-in high-performance joint impedance controller (RDK control mode: NRT_JOINT_IMPEDANCE):

ros2 launch flexiv_bringup rizon.launch.py robot_sn:=[robot_sn] rdk_control_mode:=joint_impedance

If you don’t have an real robot connected, you can test with the simulated hardware:

ros2 launch flexiv_bringup rizon.launch.py robot_sn:=dont-care use_fake_hardware:=true

which will use the mock_components simulated hardware interface instead of flexiv_hardware for real robot.

flexiv_controllers

This package contains custom ros2_control controllers and broadcasters:

  • flexiv_robot_states_broadcaster: the broadcaster publishes the Flexiv robot states information including joint- and Cartesian-space robot states, to the /${robot_sn}/flexiv_robot_states topic.

  • gpio_controller: the controller controls the GPIOs of the Flexiv robot controller.

flexiv_description

This package contains xacro files to generate URDF with accurate kinematics but approximated dynamics parameters, as well as mesh files for visualization. In addition, it contains a launch file that visualizes the robot without accessing a real robot:

ros2 launch flexiv_description view_rizon.launch.py gui:=true

flexiv_gripper

This package contains the gripper action server to interface with the gripper that is connected to the robot.

Start the flexiv_gripper_node with the following launch file, the default gripper is Flexiv Grav (Flexiv-GN01):

ros2 launch flexiv_gripper flexiv_gripper.launch.py robot_sn:=[robot_sn] gripper_name:=Flexiv-GN01

Or, start the gripper control with the robot driver if the gripper is Flexiv Grav:

ros2 launch flexiv_bringup rizon.launch.py robot_sn:=[robot_sn] load_gripper:=true

In a new terminal, send the gripper action move goal to open or close the gripper:

# Closing the gripper
ros2 action send_goal /flexiv_gripper_node/move flexiv_msgs/action/Move "{width: 0.01, velocity: 0.1, max_force: 20}"
# Opening the gripper
ros2 action send_goal /flexiv_gripper_node/move flexiv_msgs/action/Move "{width: 0.09, velocity: 0.1, max_force: 20}"

The grasp action enables the gripper to grasp with direct force control, but it requires the mounted gripper to support direct force control. Send a grasp command to the gripper:

ros2 action send_goal /flexiv_gripper_node/grasp flexiv_msgs/action/Grasp "{force: 0}"

To stop the gripper, send a stop service call:

ros2 service call /flexiv_gripper_node/stop std_srvs/srv/Trigger {}

flexiv_hardware

This package contains the flexiv_hardware plugin needed by ros2_control. The plugin is passed to the controller manager via the robot_description topic, and provides for each joint:

  • position state interface: measured joint position.

  • velocity state interface: measured joint velocity.

  • effort state interface: measured joint torque.

  • position command interface: desired joint position.

  • velocity command interface: desired joint velocity.

  • effort command interface: desired joint torque.

flexiv_moveit_config

This package contains the configuration for MoveIt 2. The planning group of the manipulator is called rizon_arm. The joint values for the Home pose configuration is [0, -40, 0, 90, 0, 40, 0] (deg).

flexiv_msgs

This package contains messages for the measured or estimated information of the robot.

flexiv_test_nodes

This package contains the demo nodes for the examples in Demos. This package is adapted from ros2_control_test_nodes.

MoveIt

To run the MoveIt example with the real robot:

ros2 launch flexiv_bringup rizon_moveit.launch.py robot_sn:=[robot_sn]

You should be able to use the MotionPlanning plugin in RViZ to plan and execute motions with the robot.

To run MoveIt with the simulated hardware:

ros2 launch flexiv_bringup rizon_moveit.launch.py robot_sn:=dont-care use_fake_hardware:=true

Demos

This section provides examples with the executable nodes in the flexiv_test_nodes package.

Joint position control

First start the robot with rizon_arm_controller:

ros2 launch flexiv_bringup rizon.launch.py robot_sn:=[robot_sn] robot_controller:=rizon_arm_controller

Then in a new terminal run the test program to send joint position commands to the controller:

ros2 launch flexiv_bringup test_joint_trajectory_controller.launch.py

After a few seconds, the robot joints will move to the position goals defined in flexiv_bringup/config/joint_trajectory_position_publisher.yaml