You're reading the documentation for a development version. For the latest released version, please have a look at Iron.

Example 8: Industrial Robots with an exposed transmission interface

RRBot, or ‘’Revolute-Revolute Manipulator Robot’’, is a simple 3-linkage, 2-joint arm that we will use to demonstrate various features.

In this example, both joints use an exposed transmission interface:

  • The communication is done using proprietary API to communicate with the robot control box.

  • Data for all joints is exchanged at once.

Note

The commands below are given for a local installation of this repository and its dependencies as well as for running them from a docker container. For more information on the docker usage see Using Docker.

Tutorial steps

  1. To check that RRBot descriptions are working properly use following launch commands

    ros2 launch ros2_control_demo_example_8 view_robot.launch.py
    

    Note

    Getting the following output in terminal is OK: Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist. This happens because joint_state_publisher_gui node need some time to start. The joint_state_publisher_gui provides a GUI to change the configuration for rrbot. It is immediately displayed in RViz.

  2. To start RRBot example open a terminal, source your ROS2-workspace and execute its launch file with

    ros2 launch ros2_control_demo_example_8 rrbot_transmissions_system_position_only.launch.py
    

    The launch file loads and starts the robot hardware, controllers and opens RViz. In starting terminal you will see a lot of output from the hardware implementation showing its internal states. This is only of exemplary purposes and should be avoided as much as possible in a hardware interface implementation.

    If you can see two orange and one yellow rectangle in in RViz everything has started properly. Still, to be sure, let’s introspect the control system before moving RRBot.

  3. Check if the hardware interface loaded properly, by opening another terminal and executing

    ros2 control list_hardware_interfaces
    
    command interfaces
          joint1/position [available] [claimed]
          joint2/position [available] [claimed]
    state interfaces
          joint1/position
          joint2/position
    

    Marker [claimed] by command interfaces means that a controller has access to command RRBot.

  4. Check if controllers are running by

    ros2 control list_controllers
    
    joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active
    forward_position_controller[forward_command_controller/ForwardCommandController] active
    
  5. If you get output from above you can send commands to Forward Command Controller, either:

    1. Manually using ROS 2 CLI interface:

    ros2 topic pub /forward_position_controller/commands std_msgs/msg/Float64MultiArray "data:
    - 0.5
    - 0.5"
    
    1. Or you can start a demo node which sends two goals every 5 seconds in a loop

    ros2 launch ros2_control_demo_example_8 test_forward_position_controller.launch.py
    

    You should now see orange and yellow blocks moving in RViz. Also, you should see changing states in the terminal where launch file is started, e.g.

    [RRBotTransmissionsSystemPositionOnlyHardware]: Command data:
      joint1: 0.5 --> transmission1(R=2) --> actuator1: 1
       joint2: 0.5 --> transmission2(R=4) --> actuator2: 2
    [RRBotTransmissionsSystemPositionOnlyHardware]: State data:
       joint1: 0.383253 <-- transmission1(R=2) <-- actuator1: 0.766505
       joint2: 0.383253 <-- transmission2(R=4) <-- actuator2: 1.53301
    

Files used for this demos

Controllers from this demo