82 lines
No EOL
3.1 KiB
XML
82 lines
No EOL
3.1 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
<xacro:macro name="rasmt_single_control" params="prefix sim">
|
|
<!-- arg for control mode -->
|
|
<ros2_control name="rasmt_single_hi" type="system">
|
|
|
|
<xacro:if value="${sim}">
|
|
<hardware>
|
|
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
|
|
</hardware>
|
|
</xacro:if>
|
|
|
|
<xacro:unless value="${sim}">
|
|
<hardware>
|
|
<plugin>fake_components/GenericSystem</plugin>
|
|
</hardware>
|
|
</xacro:unless>
|
|
|
|
<joint name="${prefix}_Rot_Z_1">
|
|
<command_interface name="position">
|
|
<!-- better to use radians as min max first -->
|
|
<param name="min">-1</param>
|
|
<param name="max"> 1</param>
|
|
</command_interface>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
|
|
<joint name="${prefix}_Rot_Y_1">
|
|
<command_interface name="position">
|
|
<param name="min">-1</param>
|
|
<param name="max"> 1</param>
|
|
</command_interface>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
|
|
<joint name="${prefix}_Rot_Z_2">
|
|
<command_interface name="position">
|
|
<param name="min">-1</param>
|
|
<param name="max"> 1</param>
|
|
</command_interface>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
|
|
<joint name="${prefix}_Rot_Y_2">
|
|
<command_interface name="position">
|
|
<param name="min">-1</param>
|
|
<param name="max"> 1</param>
|
|
</command_interface>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
|
|
<joint name="${prefix}_Rot_Z_3">
|
|
<command_interface name="position">
|
|
<param name="min">-1</param>
|
|
<param name="max"> 1</param>
|
|
</command_interface>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
|
|
<joint name="${prefix}_Rot_Y_4">
|
|
<command_interface name="position">
|
|
<param name="min">-1</param>
|
|
<param name="max"> 1</param>
|
|
</command_interface>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
|
|
</ros2_control>
|
|
</xacro:macro>
|
|
</robot> |