runtime/rasmt_support/urdf/tools/rasmt_hand_control.xacro

44 lines
No EOL
1.6 KiB
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rasmt_hand_hi" params="prefix sim">
<!-- arg for control mode -->
<ros2_control name="rasmt_hand_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}_Slide_1">
<command_interface name="position">
<!-- better to use radians as min max first -->
<param name="min">0</param>
<param name="max">10</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}_Slide_2">
<!-- <param name="mimic">${prefix}_Slide_1</param>
<param name="multiplier">1</param> -->
<command_interface name="position">
<param name="min">0</param>
<param name="max">10</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>