Skip to content

Commit

Permalink
Change joint limit and J2 movement direction_v20230718
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Jul 18, 2023
1 parent d012a3d commit 869783c
Showing 1 changed file with 14 additions and 13 deletions.
27 changes: 14 additions & 13 deletions mycobot_description/urdf/myarm/myarm_urdf.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm/j2.dae"/>
</geometry>
<origin xyz = "0.0 0 0.0 " rpy = " 3.14159 3.14159 1.5708 "/>
<origin xyz = "0.0 0 0.0 " rpy = " 3.14159 0 -1.5708 "/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm/j2.dae"/>
</geometry>
<origin xyz = "0.0 0 0.0 " rpy = " 3.14159 3.14159 1.5708"/>
<origin xyz = "0.0 0 0.0 " rpy = " 3.14159 0 -1.5708"/>
</collision>
</link>

Expand All @@ -55,13 +55,13 @@

<mesh filename="package://mycobot_description/urdf/myarm/j3.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.054 " rpy = " 0 0 3.14159"/>
<origin xyz = "0.0 0 -0.054 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm/j3.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.054" rpy = " 0 0 3.14159"/>
<origin xyz = "0.0 0 -0.054" rpy = " 0 0 0"/>
</collision>
</link>

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

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

<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-1.5708" upper = "1.39" velocity = "0"/>
<limit effort = "1000.0" lower = "-1.3962" upper = "1.3962" velocity = "0"/>
<parent link="joint1"/>
<child link="joint2"/>
<origin xyz= "0 0 0" rpy = "1.5708 3.14159 0"/>
<!-- <origin xyz= "0 0 0" rpy = "1.5708 3.14159 0"/> -->
<origin xyz= "0 0 0" rpy = "-1.5708 0 0"/>
</joint>


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

<joint name="joint4_to_joint3" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-1.91" upper = "1.39" velocity = "0"/>
<limit effort = "1000.0" lower = "-1.7453" upper = "1.3962" velocity = "0"/>
<parent link="joint3"/>
<child link="joint4"/>
<origin xyz= "0.0 0 0.0" rpy = "-1.5708 0 0"/>
<origin xyz= "0.0 0 0.0" rpy = "-1.5708 0 3.14159"/>
</joint>


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

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

<joint name="joint7_to_joint6" 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.8797" upper = "2.8797" velocity = "0"/>
<parent link="joint6"/>
<child link="joint7"/>
<origin xyz= "0 -0.056 0" rpy = "1.5708 0 0"/>
Expand Down

0 comments on commit 869783c

Please sign in to comment.