github_url: | https://github.com/ros-controls/ros2_control_demos/blob/{REPOS_FILE_BRANCH}/example_8/doc/userdoc.rst |
---|
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.
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 becausejoint_state_publisher_gui
node need some time to start. Thejoint_state_publisher_gui
provides a GUI to change the configuration for rrbot. It is immediately displayed in RViz.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.
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.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
If you get output from above you can send commands to Forward Command Controller, either:
- Manually using ROS 2 CLI interface:
ros2 topic pub /forward_position_controller/commands std_msgs/msg/Float64MultiArray "data: - 0.5 - 0.5"
- 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.
[ros2_control_node-1] [INFO] [1728857106.562714002] [controller_manager.resource_manager.hardware_component.system.RRBotTransmissionsSystemPositionOnly]: Command data: [ros2_control_node-1] joint1: 0.5 --> transmission1(R=2) --> actuator1: 1 [ros2_control_node-1] joint2: 0.5 --> transmission2(R=4) --> actuator2: 2 [ros2_control_node-1] [INFO] [1728857106.762624114] [controller_manager.resource_manager.hardware_component.system.RRBotTransmissionsSystemPositionOnly]: State data: [ros2_control_node-1] joint1: 0.166196 <-- transmission1(R=2) <-- actuator1: 0.332392 [ros2_control_node-1] joint2: 0.166196 <-- transmission2(R=4) <-- actuator2: 0.664784
- Launch file: rrbot_transmissions_system_position_only.launch.py
- Controllers yaml: rrbot_controllers.yaml
- URDF file: rrbot_transmissions_system_position_only.urdf.xacro
- Description: rrbot_description.urdf.xacro
ros2_control
tag: rrbot_transmissions_system_position_only.ros2_control.xacro
- RViz configuration: rrbot.rviz
- Hardware interface plugin: rrbot_transmissions_system_position_only.cpp
Joint State Broadcaster
(ros2_controllers repository): :ref:`doc <joint_state_broadcaster_userdoc>`Forward Command Controller
(ros2_controllers repository): :ref:`doc <forward_command_controller_userdoc>`