How to define transmissions with ros2 control
From my current understanding, if you want to use ROS2 Control with gazebo, you have to use one ros2_control
tag with type system
for all joints. (See https://github.com/ros-simulation/gaz...)
My question now: How do you define your transmissions?
I found this components_architecture_and_urdf_examples, but I can't find anything there.
Robot Description: I have 3 wheels that control the movement of the robot. Each of them has its own actuator. All of them have the same transmission ratio.
I would like to define three SimpleTansmission
s, but how do I specify the corresponding joints?
All examples I found define the transmission inside of <ros2_control name="..." type="actuator">
and not <ros2_control name="..." type="system">
.
The only system
transmission I could find, looks like this:
<transmission name="transmission1">
<plugin>transmission_interface/SomeComplex2by2Transmission</plugin>
<param name="joints">{joint1, joint2}</param>
<param name="output">{output2, output2}</param>
<param name="joint1_output1">1.5</param>
<param name="joint1_output2">3.2</param>
<param name="joint2_output1">3.1</param>
<param name="joint2_output2">1.4</param>
</transmission>
And as far as I know, this is only a prototype. There is no SomeComplex2by2Transmission
plugin.
Currently, I see two possible solutions:
- It is somehow possible to use
type="actuator"
withgazebo_ros2_control
. - There is some way to define simple transmissions in a system.
- I have to write my own transmission plugin.
I would prefer the first option, because this is way easier to maintain with xacro.
Some links:
- ROS2 Control Documentation: https://ros-controls.github.io/contro...
- ROS2 Control Demo: https://github.com/ros-controls/ros2_...
- Gazebo ROS2 Control Plugin: https://github.com/ros-simulation/gaz...
My current ros2_control
tag:
<!-- ROS Control for the rims -->
<ros2_control name="cassiopeia_rim_control" type="system">
<xacro:if value="$(arg use_sim)">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
</xacro:if>
<xacro:unless value="$(arg use_sim)">
<hardware>
<xacro:if value="$(arg use_fake_hardware)">
<plugin>fake_components/GenericSystem</plugin>
<param name="fake_sensor_commands">$(arg fake_sensor_commands)</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="$(arg use_fake_hardware)">
<!-- TODO: If we want this feature, we have to write an
hardware controller plugin in C++ for ROS2 Control.
-->
</xacro:unless>
</hardware>
</xacro:unless>
<joint name="a_rim_joint">
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="b_rim_joint">
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="c_rim_joint">
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find pkg_name)/config/controllers.yaml</parameters>
</plugin>
</gazebo>