]> defiant.homedns.org Git - arm_ros_conn.git/commitdiff
urdf joint angle to hw
authorErik Andresen <erik@vontaene.de>
Sat, 7 Nov 2015 10:06:48 +0000 (11:06 +0100)
committerErik Andresen <erik@vontaene.de>
Sat, 7 Nov 2015 10:06:48 +0000 (11:06 +0100)
urdf/arm.urdf

index a8c95387e396ae449f7e9f7c26272701fc4600d1..0bd19074a6d6d14d13a3e7381e886ff5680bbc8f 100644 (file)
                </visual>
        </link>
 
-       <joint name="base_link_to_plate" type="fixed">
+       <joint name="plate_joint" type="fixed">
                <parent link="base_link"/>
                <child link="plate"/>
                <origin xyz="0 0 0.00375"/>
        </joint>
 
-       <joint name="plate_to_arm_base" type="fixed">
+       <joint name="arm_base_joint" type="fixed">
                <parent link="plate"/>
                <child link="arm_base"/>
                <origin xyz="0 0.099 0"/>
        </joint>
 
-       <joint name="arm_base_to_link1" type="revolute">
+       <joint name="link1_joint" type="revolute">
                <parent link="arm_base"/>
                <child link="link1"/>
-               <axis xyz="0 0 1"/>
-               <limit effort="1000.0" lower="-5.672320068981571" upper="0.0" velocity="1.0"/>
+               <axis xyz="0 0 -1"/>
+               <limit effort="1000.0" lower="0.0" upper="5.672320068981571" velocity="1.0"/>
        </joint>
 
-       <joint name="link_1_2_joint" type="revolute">
+       <joint name="link2_joint" type="revolute">
                <parent link="link1"/>
                <child link="link2"/>
-               <axis xyz="0 1 0"/>
-               <origin xyz="0.0 0.0 0.123" rpy="0 0 0"/>
-               <limit effort="1000.0" lower="-2.0402" upper="1.4203" velocity="1.0"/>
+               <axis xyz="0 -1 0"/>
+               <origin xyz="0.0 0.0 0.123" rpy="0 1.5708 0"/>
+               <limit effort="1000.0" lower="0.1505" upper="3.611" velocity="1.0"/>
        </joint>
 
-       <joint name="link_2_3_joint" type="revolute">
+       <joint name="link3_joint" type="revolute">
                <parent link="link2"/>
                <child link="link3"/>
                <axis xyz="0 1 0"/>
-               <origin xyz="0 0 0.240" rpy="0 0 0"/>
-               <limit effort="1000.0" lower="-1.5708" upper="1.5708" velocity="1.0"/>
+               <origin xyz="0 0 0.240" rpy="0 -1.5708 0"/>
+               <limit effort="1000.0" lower="0" upper="3.1416" velocity="1.0"/>
        </joint>
 
-       <joint name="link_3_4_joint" type="revolute">
+       <joint name="link4_joint" type="revolute">
                <parent link="link3"/>
                <child link="link4"/>
-               <axis xyz="0 0 1"/>
+               <axis xyz="0 0 -1"/>
                <origin xyz="0 0 0.135" rpy="0 0 0"/>
-               <limit effort="1000.0" lower="-5.4978" upper="0.15708" velocity="1.0"/>
+               <limit effort="1000.0" lower="-0.15708" upper="5.4978" velocity="1.0"/>
        </joint>
 
-       <joint name="link_4_5_joint" type="revolute">
+       <joint name="link5_joint" type="revolute">
                <parent link="link4"/>
                <child link="link5"/>
-               <axis xyz="0 1 0"/>
+               <axis xyz="0 -1 0"/>
                <origin xyz="0 0 0.06" rpy="0 0 0"/>
                <limit effort="1000.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
        </joint>