Skip to content

Commit 33c8de0

Browse files
committed
Fix xacro
1 parent be1cfc0 commit 33c8de0

1 file changed

Lines changed: 5 additions & 6 deletions

File tree

Industrial/ros2_SimRealRobotControl_gz/ros2srrc_endeffectors/robotiq_2f85/urdf/robotiq_2f85_macro.urdf.xacro

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -166,8 +166,7 @@
166166
<child link="robotiq_85_right_knuckle_link"/>
167167
<axis xyz="0 0 1"/>
168168
<origin rpy="0 0 0" xyz="0.05490451627 -0.03060114443 0.0"/>
169-
<limit lower="-0.05" upper="0.80285" velocity="0.5" effort="1000"/>
170-
<dynamics damping="1.0" friction="1.0"/>
169+
<mimic joint="robotiq_85_left_knuckle_joint" multiplier="1"/>
171170
</joint>
172171

173172
<!-- Robotiq: left_finger -->
@@ -252,7 +251,7 @@
252251
<child link="robotiq_85_left_inner_knuckle_link"/>
253252
<axis xyz="0 0 1"/>
254253
<origin xyz="0.06142 0.0127 0" rpy="${pi} 0.0 0.0" />
255-
<limit lower="-0.05" upper="0.80285" velocity="0.5" effort="1000"/>
254+
<mimic joint="robotiq_85_left_knuckle_joint" multiplier="1"/>
256255
<dynamics damping="1.0" friction="1.0"/>
257256
</joint>
258257

@@ -282,7 +281,7 @@
282281
<child link="robotiq_85_right_inner_knuckle_link"/>
283282
<axis xyz="0 0 1"/>
284283
<origin xyz="0.06142 -0.0127 0" rpy="0 0 0"/>
285-
<limit lower="-0.05" upper="0.80285" velocity="0.5" effort="1000"/>
284+
<mimic joint="robotiq_85_left_knuckle_joint" multiplier="1"/>
286285
<dynamics damping="1.0" friction="1.0"/>
287286
</joint>
288287

@@ -314,7 +313,7 @@
314313
<child link="robotiq_85_left_finger_tip_link"/>
315314
<axis xyz="0 0 1"/>
316315
<origin xyz="0.04303959807 -0.03759940821 0.0" rpy="0.0 0.0 0.0"/>
317-
<limit lower="-0.80285" upper="0.05" velocity="0.5" effort="1000"/>
316+
<mimic joint="robotiq_85_left_knuckle_joint" multiplier="-1"/>
318317
<dynamics damping="1.0" friction="1.0"/>
319318
</joint>
320319

@@ -346,7 +345,7 @@
346345
<child link="robotiq_85_right_finger_tip_link"/>
347346
<axis xyz="0 0 1"/>
348347
<origin rpy="0.0 0.0 0.0" xyz="0.04303959807 -0.03759940821 0.0"/>
349-
<limit lower="-0.80285" upper="0.05" velocity="0.5" effort="1000"/>
348+
<mimic joint="robotiq_85_left_knuckle_joint" multiplier="-1"/>
350349
<dynamics damping="1.0" friction="1.0"/>
351350
</joint>
352351

0 commit comments

Comments
 (0)