Skip to content

Commit

Permalink
update myarm_urdf joint limit
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Jul 3, 2023
1 parent 7063aa9 commit e743a71
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions mycobot_description/urdf/myarm/myarm_urdf.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@

<joint name="joint1_to_base" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14" velocity = "0"/>
<limit effort = "1000.0" lower = "-2.79" upper = "2.87" velocity = "0"/>
<parent link="base"/>
<child link="joint1"/>
<origin xyz= "0 0 0.165" rpy = "0 0 0"/>
Expand All @@ -147,7 +147,7 @@

<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-1.5708" upper = "1.5708" velocity = "0"/>
<limit effort = "1000.0" lower = "-1.5708" upper = "1.39" 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 = "-3.14" upper = "3.14" velocity = "0"/>
<limit effort = "1000.0" lower = "-3.05" upper = "3.05" 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 = "-1.5708" upper = "1.5708" velocity = "0"/>
<limit effort = "1000.0" lower = "-1.91" upper = "1.39" velocity = "0"/>
<parent link="joint3"/>
<child link="joint4"/>
<origin xyz= "0.0 0 0.0" rpy = "-1.5708 0 0"/>
Expand All @@ -175,7 +175,7 @@

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

<joint name="joint6_to_joint5" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-1.5708" upper = "1.5708" velocity = "0"/>
<limit effort = "1000.0" lower = "-1.91" upper = "1.91" velocity = "0"/>
<parent link="joint5"/>
<child link="joint6"/>
<origin xyz= "0 0.0 0" rpy = "-1.5708 0 0"/>
Expand Down

0 comments on commit e743a71

Please sign in to comment.