Skip to content

Commit

Permalink
Update mycobot_urdf.urdf
Browse files Browse the repository at this point in the history
  • Loading branch information
Johnkey00 committed Aug 13, 2024
1 parent 834abba commit 9b139bd
Showing 1 changed file with 7 additions and 8 deletions.
15 changes: 7 additions & 8 deletions mycobot_description/urdf/mycobot/mycobot_urdf.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@

<joint name="g_base_to_joint1" type="fixed">
<axis xyz="0 0 0"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<limit effort = "1000.0" lower = "0" upper = "0" velocity = "1"/>
<parent link="g_base"/>
<child link="joint1"/>
<origin xyz= "0 0 0" rpy = "0 0 0"/>
Expand All @@ -151,7 +151,7 @@

<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<limit effort = "1000.0" lower = "-2.93" upper = "2.9321" velocity = "1"/>
<parent link="joint1"/>
<child link="joint2"/>
<origin xyz= "0 0 0.13156" rpy = "0 0 0"/>
Expand All @@ -160,7 +160,7 @@

<joint name="joint3_to_joint2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<limit effort = "1000.0" lower = "-2.36" upper = "2.3561" velocity = "1"/>
<parent link="joint2"/>
<child link="joint3"/>
<origin xyz= "0 0 0" rpy = "0 1.5708 -1.5708"/>
Expand All @@ -169,33 +169,32 @@

<joint name="joint4_to_joint3" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<limit effort = "1000.0" lower = "-2.62" upper = "2.6179" velocity = "0"/>
<parent link="joint3"/>
<child link="joint4"/>
<origin xyz= " -0.1104 0 0 " rpy = "0 0 0"/>
</joint>



<joint name="joint5_to_joint4" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<limit effort = "1000.0" lower = "-2.53" upper = "2.5307" velocity = "0"/>
<parent link="joint4"/>
<child link="joint5"/>
<origin xyz= "-0.096 0 0.06462" rpy = "0 0 -1.5708"/>
</joint>

<joint name="joint6_to_joint5" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<limit effort = "1000.0" lower = "-2.88" upper = "2.8797" velocity = "1"/>
<parent link="joint5"/>
<child link="joint6"/>
<origin xyz= "0 -0.07318 0" rpy = "1.5708 -1.5708 0"/>
</joint>

<joint name="joint6output_to_joint6" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "1"/>
<parent link="joint6"/>
<child link="joint6_flange"/>
<origin xyz= "0 0.0456 0" rpy = "-1.5708 0 0"/>
Expand Down

0 comments on commit 9b139bd

Please sign in to comment.