change gripper control from moveit to ros2_control

This commit is contained in:
Ilya Uraev 2022-03-08 00:42:34 +04:00
parent 27271c0e06
commit b4339edc19
13 changed files with 116 additions and 43 deletions

View file

@ -409,13 +409,13 @@
<axis xyz="0 0 0"/>
</joint>
<link name="${prefix}_tool_end_point"/>
<!--link name="${prefix}_tool_end_point"/>
<joint name="${prefix}_tool_end_point_to_tool0" type="fixed">
<parent link="${prefix}_tool0"/>
<parent link="${prefix}_Dock_Link"/>
<child link="${prefix}_tool_end_point"/>
<origin xyz="0 0 ${gripper_length}" rpy="0 0 0"/>
<origin xyz="0 0 ${gripper_length+0.12324}" rpy="0 0 0"/>
<axis xyz="0 0 0"/>
</joint>
</joint-->
</xacro:macro>
</robot>

View file

@ -17,10 +17,10 @@
</xacro:unless>
<joint name="${prefix}_Slide_1">
<command_interface name="position">
<command_interface name="effort">
<!-- better to use radians as min max first -->
<param name="min">-1</param>
<param name="max"> 1</param>
<param name="min">-10</param>
<param name="max">10</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
@ -30,9 +30,9 @@
<joint name="${prefix}_Slide_2">
<!-- <param name="mimic">${prefix}_Slide_1</param>
<param name="multiplier">1</param> -->
<command_interface name="position">
<param name="min">-1</param>
<param name="max"> 1</param>
<command_interface name="effort">
<param name="min">-10</param>
<param name="max">10</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>