Skip to content

Commit

Permalink
update mercury urdf joint range
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Dec 7, 2023
1 parent 48c57bc commit e1fb985
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 12 deletions.
14 changes: 7 additions & 7 deletions mycobot_description/urdf/mercury_a1/mercury_a1.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@

<joint name="joint1_to_base" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-2.8797" upper = "2.8797" velocity = "0"/>
<limit effort = "1000.0" lower = "-3.1066" upper = "3.1066" velocity = "0"/>
<parent link="base"/>
<child link="joint1"/>
<origin xyz= "0 0 0.175" rpy = "0 0 0"/>
Expand All @@ -146,7 +146,7 @@

<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-1.7453" upper = "1.7453" velocity = "0"/>
<limit effort = "1000.0" lower = "-1.4311" upper = "2.2689" velocity = "0"/>
<parent link="joint1"/>
<child link="joint2"/>
<!-- <origin xyz= "0 0 0" rpy = "1.5708 3.14159 0"/> -->
Expand All @@ -156,7 +156,7 @@

<joint name="joint3_to_joint2" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-2.8797" upper = "2.8797" velocity = "0"/>
<limit effort = "1000.0" lower = "-3.1066" upper = "3.1066" velocity = "0"/>
<parent link="joint2"/>
<child link="joint3"/>
<origin xyz= "0 -0.11 0 " rpy = "1.5708 0 0"/>
Expand All @@ -166,7 +166,7 @@

<joint name="joint4_to_joint3" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-3.0543" upper = "0.0174" velocity = "0"/>
<limit effort = "1000.0" lower = "-3.0543" upper = "0.2617" velocity = "0"/>
<parent link="joint3"/>
<child link="joint4"/>
<origin xyz= "0.03 0 0.095" rpy = "-1.5708 0 3.14159"/>
Expand All @@ -175,7 +175,7 @@

<joint name="joint5_to_joint4" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-2.8797" upper = "2.8797" velocity = "0"/>
<limit effort = "1000.0" lower = "-3.1066" upper = "3.1066" velocity = "0"/>
<parent link="joint4"/>
<child link="joint5"/>
<origin xyz= "0.03 -0.126 0" rpy = "1.5708 3.14159 0"/>
Expand All @@ -184,15 +184,15 @@

<joint name="joint6_to_joint5" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-0.0174" upper = "3.14159" velocity = "0"/>
<limit effort = "1000.0" lower = "-0.0349" upper = "2.9321" velocity = "0"/>
<parent link="joint5"/>
<child link="joint6"/>
<origin xyz= "0 0.0 0.08" rpy = "1.5708 0 0"/>
</joint>

<joint name="joint7_to_joint6" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-2.8797" upper = "2.8797" velocity = "0"/>
<limit effort = "1000.0" lower = "-3.1066" upper = "3.1066" velocity = "0"/>
<parent link="joint6"/>
<child link="joint7"/>
<origin xyz= "0.038 -0.046 0" rpy = "1.5708 0 0"/>
Expand Down
10 changes: 5 additions & 5 deletions mycobot_description/urdf/mercury_b1/mercury_b1.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -57,13 +57,13 @@
<geometry>
<mesh filename="package://mycobot_description/urdf/mercury_b1/head_eye.dae"/>
</geometry>
<origin xyz = "0 0 -0.0 " rpy = " 0 0 0"/>
<origin xyz = "0 0 -0.0 " rpy = " 0 0 3.14159"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mercury_b1/head_eye.dae"/>
</geometry>
<origin xyz = "0 0 -0.1 " rpy = " 0 0 0"/>
<origin xyz = "0 0 -0.1 " rpy = " 0 0 3.14159"/>
</collision>
</link>

Expand Down Expand Up @@ -319,7 +319,7 @@

<joint name="joint6_L" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-0.0174" upper = "2.9321" velocity = "0"/>
<limit effort = "1000.0" lower = "-0.0349" upper = "2.9321" velocity = "0"/>
<parent link="link5_L"/>
<child link="link6_L"/>
<origin xyz= " 0 0 0.08" rpy = "1.5708 0 0"/>
Expand Down Expand Up @@ -375,7 +375,7 @@

<joint name="joint6_R" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-0.0174" upper = "2.9321" velocity = "0"/>
<limit effort = "1000.0" lower = "-0.0349" upper = "2.9321" velocity = "0"/>
<parent link="link5_R"/>
<child link="link6_R"/>
<origin xyz= " 0 0 0.08" rpy = "1.5708 0 0"/>
Expand All @@ -395,7 +395,7 @@
<limit effort = "1000.0" lower = "0" upper = "0.8377" velocity = "0"/>
<parent link="link_head"/>
<child link="link_eye"/>
<origin xyz= " 0.03 0 -0.08 " rpy = "1.5708 0 0"/>
<origin xyz= " 0.03 0 -0.08 " rpy = "1.5708 0 3.14"/>
</joint>

<joint name="head" type="revolute">
Expand Down

0 comments on commit e1fb985

Please sign in to comment.