Skip to content

Commit

Permalink
Unify 2F_85 and 2F_140 link names
Browse files Browse the repository at this point in the history
  • Loading branch information
Karanbir Chahal committed Sep 26, 2024
1 parent 27ecc36 commit 129dac7
Show file tree
Hide file tree
Showing 3 changed files with 47 additions and 47 deletions.
2 changes: 1 addition & 1 deletion robotiq_description/config/robotiq_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ controller_manager:
robotiq_gripper_controller:
ros__parameters:
default: true
joint: robotiq_85_left_knuckle_joint
joint: left_knuckle_joint
use_effort_interface: true
use_speed_interface: true

Expand Down
12 changes: 6 additions & 6 deletions robotiq_description/urdf/2f_85.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@

<!-- Joint interfaces -->
<!-- With Gazebo or Hardware, they handle mimic joints, so we only need this command interface activated -->
<joint name="${prefix}robotiq_85_left_knuckle_joint">
<joint name="${prefix}left_knuckle_joint">
<command_interface name="position" />
<state_interface name="position">
<param name="initial_value">0.7929</param>
Expand All @@ -53,31 +53,31 @@
</joint>
<!-- When simulating we need to include the rest of the gripper joints -->
<xacro:if value="${use_fake_hardware or sim_isaac or sim_gazebo}">
<joint name="${prefix}robotiq_85_right_knuckle_joint">
<joint name="${prefix}right_knuckle_joint">
<xacro:unless value="${sim_gazebo}">
<state_interface name="position"/>
<state_interface name="velocity"/>
</xacro:unless>
</joint>
<joint name="${prefix}robotiq_85_left_inner_knuckle_joint">
<joint name="${prefix}left_inner_knuckle_joint">
<xacro:unless value="${sim_gazebo}">
<state_interface name="position"/>
<state_interface name="velocity"/>
</xacro:unless>
</joint>
<joint name="${prefix}robotiq_85_right_inner_knuckle_joint">
<joint name="${prefix}right_inner_knuckle_joint">
<xacro:unless value="${sim_gazebo}">
<state_interface name="position"/>
<state_interface name="velocity"/>
</xacro:unless>
</joint>
<joint name="${prefix}robotiq_85_left_finger_tip_joint">
<joint name="${prefix}left_finger_tip_joint">
<xacro:unless value="${sim_gazebo}">
<state_interface name="position"/>
<state_interface name="velocity"/>
</xacro:unless>
</joint>
<joint name="${prefix}robotiq_85_right_finger_tip_joint">
<joint name="${prefix}right_finger_tip_joint">
<xacro:unless value="${sim_gazebo}">
<state_interface name="position"/>
<state_interface name="velocity"/>
Expand Down
80 changes: 40 additions & 40 deletions robotiq_description/urdf/robotiq_2f_85_macro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
com_port="${com_port}"/>
</xacro:if>

<link name="${prefix}robotiq_85_base_link">
<link name="${prefix}robotiq_base_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/robotiq_base.dae" />
Expand All @@ -47,7 +47,7 @@
</inertial>
</link>

<link name="${prefix}robotiq_85_left_knuckle_link">
<link name="${prefix}left_knuckle_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/left_knuckle.dae" />
Expand All @@ -65,7 +65,7 @@
</inertial>
</link>

<link name="${prefix}robotiq_85_right_knuckle_link">
<link name="${prefix}right_knuckle_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/right_knuckle.dae" />
Expand All @@ -83,7 +83,7 @@
</inertial>
</link>

<link name="${prefix}robotiq_85_left_finger_link">
<link name="${prefix}left_finger_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/left_finger.dae" />
Expand All @@ -101,7 +101,7 @@
</inertial>
</link>

<link name="${prefix}robotiq_85_right_finger_link">
<link name="${prefix}right_finger_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/right_finger.dae" />
Expand All @@ -119,7 +119,7 @@
</inertial>
</link>

<link name="${prefix}robotiq_85_left_inner_knuckle_link">
<link name="${prefix}left_inner_knuckle_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/left_inner_knuckle.dae" />
Expand All @@ -137,7 +137,7 @@
</inertial>
</link>

<link name="${prefix}robotiq_85_right_inner_knuckle_link">
<link name="${prefix}right_inner_knuckle_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/right_inner_knuckle.dae" />
Expand All @@ -155,7 +155,7 @@
</inertial>
</link>

<link name="${prefix}robotiq_85_left_finger_tip_link">
<link name="${prefix}left_finger_tip_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/left_finger_tip.dae" />
Expand Down Expand Up @@ -191,7 +191,7 @@
</inertial>
</link>

<link name="${prefix}robotiq_85_right_finger_tip_link">
<link name="${prefix}right_finger_tip_link">
<visual>
<geometry>
<mesh filename="file://$(find robotiq_description)/meshes/visual/2f_85/right_finger_tip.dae" />
Expand Down Expand Up @@ -227,71 +227,71 @@
</inertial>
</link>

<joint name="${prefix}robotiq_85_base_joint" type="fixed">
<joint name="${prefix}base_joint" type="fixed">
<parent link="${parent}" />
<child link="${prefix}robotiq_85_base_link" />
<child link="${prefix}robotiq_base_link" />
<xacro:insert_block name="origin" />
</joint>

<joint name="${prefix}robotiq_85_left_knuckle_joint" type="revolute">
<parent link="${prefix}robotiq_85_base_link" />
<child link="${prefix}robotiq_85_left_knuckle_link" />
<joint name="${prefix}left_knuckle_joint" type="revolute">
<parent link="${prefix}robotiq_base_link" />
<child link="${prefix}left_knuckle_link" />
<axis xyz="0 -1 0" />
<origin xyz="0.03060114 0.0 0.05490452" rpy="0 0 0" />
<limit lower="0.0" upper="0.8" velocity="0.5" effort="50" />
</joint>

<joint name="${prefix}robotiq_85_right_knuckle_joint" type="revolute">
<parent link="${prefix}robotiq_85_base_link" />
<child link="${prefix}robotiq_85_right_knuckle_link" />
<joint name="${prefix}right_knuckle_joint" type="revolute">
<parent link="${prefix}robotiq_base_link" />
<child link="${prefix}right_knuckle_link" />
<axis xyz="0 -1 0" />
<origin xyz="-0.03060114 0.0 0.05490452" rpy="0 0 0" />
<limit lower="-0.8" upper="0.0" velocity="0.5" effort="50" />
<mimic joint="${prefix}robotiq_85_left_knuckle_joint" multiplier="-1" />
<mimic joint="${prefix}left_knuckle_joint" multiplier="-1" />
</joint>

<joint name="${prefix}robotiq_85_left_finger_joint" type="fixed">
<parent link="${prefix}robotiq_85_left_knuckle_link" />
<child link="${prefix}robotiq_85_left_finger_link" />
<joint name="${prefix}left_finger_joint" type="fixed">
<parent link="${prefix}left_knuckle_link" />
<child link="${prefix}left_finger_link" />
<origin xyz="0.03152616 0.0 -0.00376347" rpy="0 0 0" />
</joint>

<joint name="${prefix}robotiq_85_right_finger_joint" type="fixed">
<parent link="${prefix}robotiq_85_right_knuckle_link" />
<child link="${prefix}robotiq_85_right_finger_link" />
<joint name="${prefix}right_finger_joint" type="fixed">
<parent link="${prefix}right_knuckle_link" />
<child link="${prefix}right_finger_link" />
<origin xyz="-0.03152616 0.0 -0.00376347" rpy="0 0 0" />
</joint>

<joint name="${prefix}robotiq_85_left_inner_knuckle_joint" type="continuous">
<parent link="${prefix}robotiq_85_base_link" />
<child link="${prefix}robotiq_85_left_inner_knuckle_link" />
<joint name="${prefix}left_inner_knuckle_joint" type="continuous">
<parent link="${prefix}robotiq_base_link" />
<child link="${prefix}left_inner_knuckle_link" />
<axis xyz="0 -1 0" />
<origin xyz="0.0127 0.0 0.06142" rpy="0 0 0" />
<mimic joint="${prefix}robotiq_85_left_knuckle_joint" />
<mimic joint="${prefix}left_knuckle_joint" />
</joint>

<joint name="${prefix}robotiq_85_right_inner_knuckle_joint" type="continuous">
<parent link="${prefix}robotiq_85_base_link" />
<child link="${prefix}robotiq_85_right_inner_knuckle_link" />
<joint name="${prefix}right_inner_knuckle_joint" type="continuous">
<parent link="${prefix}robotiq_base_link" />
<child link="${prefix}right_inner_knuckle_link" />
<axis xyz="0 -1 0" />
<origin xyz="-0.0127 0.0 0.06142" rpy="0 0 0" />
<mimic joint="${prefix}robotiq_85_left_knuckle_joint" multiplier="-1" />
<mimic joint="${prefix}left_knuckle_joint" multiplier="-1" />
</joint>

<joint name="${prefix}robotiq_85_left_finger_tip_joint" type="continuous">
<parent link="${prefix}robotiq_85_left_finger_link" />
<child link="${prefix}robotiq_85_left_finger_tip_link" />
<joint name="${prefix}left_finger_tip_joint" type="continuous">
<parent link="${prefix}left_finger_link" />
<child link="${prefix}left_finger_tip_link" />
<axis xyz="0 -1 0" />
<origin xyz="0.00563134 0.0 0.04718515" rpy="0 0 0" />
<mimic joint="${prefix}robotiq_85_left_knuckle_joint" multiplier="-1" />
<mimic joint="${prefix}left_knuckle_joint" multiplier="-1" />
</joint>

<joint name="${prefix}robotiq_85_right_finger_tip_joint" type="continuous">
<parent link="${prefix}robotiq_85_right_finger_link" />
<child link="${prefix}robotiq_85_right_finger_tip_link" />
<joint name="${prefix}right_finger_tip_joint" type="continuous">
<parent link="${prefix}right_finger_link" />
<child link="${prefix}right_finger_tip_link" />
<axis xyz="0 -1 0" />
<origin xyz="-0.00563134 0.0 0.04718515" rpy="0 0 0" />
<mimic joint="${prefix}robotiq_85_left_knuckle_joint" />
<mimic joint="${prefix}left_knuckle_joint" />
</joint>
</xacro:macro>
</robot>

0 comments on commit 129dac7

Please sign in to comment.