The topic_based system implements hardware_interface::SystemInterface
supporting command and state interfaces through ROS topic communication layer.
Follow the instructions in the MoveIt and Isaac sim integration guide to setup your robot for MoveIt and Isaac sim integration.
The topic_based system interface has a few ros2_control
urdf tags to customize its behavior.
- joint_commands_topic: (default: "/robot_joint_command"). Example:
<param name="joint_commands_topic">/my_topic_joint_commands</param>
. - joint_states_topic: (default: "/robot_joint_states"). Example:
<param name="joint_states_topic">/my_topic_joint_states</param>
. - trigger_joint_command_threshold: (default: 1e-5). Used to avoid spamming the joint command topic when the difference between the current joint state and the joint command is smaller than this value, set to -1 to always send the joint command. Example:
<param name="trigger_joint_command_threshold">0.001</param>
. - sum_wrapped_joint_states: (default: "false"). Used to track the total rotation for joint states the values reported on the
joint_commands_topic
wrap from 2pi to -2pi when rotating in the positive direction. (Isaac Sim only reports joint states from 2pi to -2pi) Example:<param name="sum_wrapped_joint_states">true</param>
.
- mimic: Defined name of the joint to mimic. This is often used concept with parallel grippers. Example:
<param name="mimic">joint1</param>
. - multiplier: Multiplier of values for mimicking joint defined in mimic parameter. Example:
<param name="multiplier">-2</param>
.
If your robot description support mock_components you only need to change <plugin>mock_components/GenericSystem</plugin>
to <plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
, make sure to add the joint_commands_topic
and joint_states_topic
to point to the correct topics.
<ros2_control name="name" type="system">
<hardware>
<plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
<param name="joint_commands_topic">/topic_based_joint_commands</param>
<param name="joint_states_topic">/topic_based_joint_states</param>
<param name="sum_wrapped_joint_states">true</param>
</hardware>
<joint name="joint_1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
...
<joint name="joint_n">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
...
<joint name="mimic_joint_1">
<param name="mimic">joint_k</param>
<param name="multiplier">1</param>
<command_interface name="position" />
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
...
<joint name="mimic_joint_n">
<param name="mimic">joint_kn</param>
<param name="multiplier">1</param>
<command_interface name="position" />
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
</ros2_control>