]> defiant.homedns.org Git - arm_ros_conn.git/blobdiff - urdf/arm.urdf
urdf: updated plate_box size
[arm_ros_conn.git] / urdf / arm.urdf
index ba1e7b862d722b09e4dfe7f4bded5d2c8c7f40ba..37a9b0c509c50d2198390207ef8434abab089c12 100644 (file)
@@ -115,6 +115,30 @@ For IKFast:
                </visual>
        </link>
 
+       <link name="link2_motor_extension">
+               <visual>
+                       <geometry>
+                               <box size="0.015 0.015 0.10"/>
+                       </geometry>
+                       <origin xyz="0 0 0.05" rpy="0 0 0"/>
+                       <material name="grey">
+                               <color rgba="0.5 0.5 0.5 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="plate_box">
+               <visual>
+                       <geometry>
+                               <box size="0.08 0.185 0.035"/>
+                       </geometry>
+                       <origin xyz="0 0 0.0175" rpy="0 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
        <joint name="plate_joint" type="fixed">
                <parent link="base_link"/>
                <child link="plate"/>
@@ -131,7 +155,7 @@ For IKFast:
                <parent link="arm_base"/>
                <child link="link1"/>
                <axis xyz="0 0 -1"/>
-               <limit effort="1.0" lower="0.0" upper="5.672320068981571" velocity="1.0"/>
+               <limit effort="1.0" lower="0.0" upper="5.672320068981571" velocity="0.2"/>
        </joint>
 
        <joint name="link2_joint" type="revolute">
@@ -139,7 +163,7 @@ For IKFast:
                <child link="link2"/>
                <axis xyz="0 0 1"/>
                <origin xyz="0.0 0.0 0.123" rpy="1.5708 0 0"/>
-               <limit effort="1.0" lower="0.1505" upper="3.611" velocity="1.0"/>
+               <limit effort="1.0" lower="0.1505" upper="3.611" velocity="0.1"/>
        </joint>
 
        <joint name="link3_joint" type="revolute">
@@ -147,7 +171,7 @@ For IKFast:
                <child link="link3"/>
                <axis xyz="0 0 -1"/>
                <origin xyz="0.240 0 0" rpy="0 0 0"/>
-               <limit effort="1.0" lower="0" upper="3.1416" velocity="1.0"/>
+               <limit effort="1.0" lower="0" upper="3.1416" velocity="0.2"/>
        </joint>
 
        <joint name="link4_joint" type="revolute">
@@ -155,7 +179,7 @@ For IKFast:
                <child link="link4"/>
                <axis xyz="0 0 -1"/>
                <origin xyz="0 0.135 0" rpy="-1.5708 0 0"/>
-               <limit effort="1.0" lower="-0.15708" upper="5.4978" velocity="1.0"/>
+               <limit effort="1.0" lower="-0.15708" upper="5.4978" velocity="0.5"/>
        </joint>
 
        <joint name="link5_joint" type="revolute">
@@ -183,7 +207,7 @@ For IKFast:
                <child link="left_gripper"/>
                <axis xyz="0 0 1"/>
                <origin xyz="0 0.015 0" rpy="0 0 0"/>
-               <limit effort="1.0" lower="0.0" upper="0.35" velocity="1.0"/>
+               <limit effort="1.0" lower="0.0" upper="0.35" velocity="0.1"/>
        </joint>
 
        <joint name="right_gripper_joint" type="revolute">
@@ -191,6 +215,18 @@ For IKFast:
                <child link="right_gripper"/>
                <axis xyz="0 0 1"/>
                <origin xyz="0 -0.015 0" rpy="3.1416 0 0"/>
-               <limit effort="1.0" lower="0.0" upper="0.35" velocity="1.0"/>
+               <limit effort="1.0" lower="0.0" upper="0.35" velocity="0.1"/>
+       </joint>
+
+       <joint name="link2_motor_extension_joint" type="fixed">
+               <parent link="link2"/>
+               <child link="link2_motor_extension"/>
+               <origin xyz="0.165 -0.03 0" rpy="1.5708 0 0"/>
+       </joint>
+
+       <joint name="plate_box_joint" type="fixed">
+               <parent link="plate"/>
+               <child link="plate_box"/>
+               <origin xyz="-0.04 -0.035 0" rpy="0 0 0"/>
        </joint>
 </robot>