]> defiant.homedns.org Git - ros_roboint.git/commitdiff
urdf: fix x center position
authorErik Andresen <erik@vontaene.de>
Tue, 17 Sep 2013 19:40:51 +0000 (21:40 +0200)
committerErik Andresen <erik@vontaene.de>
Tue, 17 Sep 2013 19:40:51 +0000 (21:40 +0200)
urdf/explorer.urdf

index af960a093ccf7df10a7abe61068beebfdf20e065..a32a1afaf50f840506c4e0c2f88182c3e67348b9 100644 (file)
@@ -5,7 +5,7 @@
                        <geometry>
                                <box size="0.14 0.155 0.085"/>
                        </geometry>
-                       <origin xyz="0.06 0 0.0525" rpy="0 0 0"/>
+                       <origin xyz="0.0 0 0.0525" rpy="0 0 0"/>
                        <material name="white_transparent">
                                <color rgba="1 1 1 0.8"/>
                        </material>
@@ -17,7 +17,6 @@
                        <geometry>
                                <box size="0.06 0.09 0.075"/>
                        </geometry>
-                       <origin xyz="0 0 0.0525" rpy="0 0 0"/>
                        <material name="red">
                                <color rgba="1 0 0 1"/>
                        </material>
                </visual>
        </link>
 
-       <link name="scan">
+       <link name="forward_sensor">
                <visual>
                        <geometry>
                                <box size="0.015 0.045 0.03"/>
                        </geometry>
-                       <origin xyz="0.065 0 0.06" rpy="0 0 0"/>
+                       <origin xyz="0 0 0" rpy="0 0 0"/>
                        <material name="black">
                                <color rgba="0 0 0 1"/>
                        </material>
        <joint name="tail_joint" type="fixed">
                <parent link="base_link"/>
                <child link="tail"/>
-               <origin xyz="-0.04 0 0.005" rpy="0 0 0"/>
+               <origin xyz="-0.1 0 0.0575" rpy="0 0 0"/>
        </joint>
 
        <joint name="left_wheel_joint" type="fixed">
                <parent link="base_link"/>
                <child link="left_wheel"/>
-               <origin xyz="0.07 -0.08 0.026" rpy="1.57 0 0"/>
+               <origin xyz="0 -0.08 0.026" rpy="1.57 0 0"/>
        </joint>
 
        <joint name="right_wheel_joint" type="fixed">
                <parent link="base_link"/>
                <child link="right_wheel"/>
-               <origin xyz="0.07 0.08 0.026" rpy="1.57 0 0"/>
+               <origin xyz="0 0.08 0.026" rpy="1.57 0 0"/>
        </joint>
 
        <joint name="aft_wheel_joint" type="fixed">
                <parent link="tail"/>
                <child link="aft_wheel"/>
-               <origin xyz="0 0 0.005" rpy="1.57 0 0"/>
+               <origin xyz="0 0 -0.0475" rpy="1.57 0 0"/>
        </joint>
 
-       <joint name="scan_joint" type="fixed">
+       <joint name="forward_sensor_joint" type="fixed">
                <parent link="base_link"/>
-               <child link="scan"/>
-               <origin xyz="0.06 0 0" rpy="0 0 0"/>
+               <child link="forward_sensor"/>
+               <origin xyz="0.07 0 0.06" rpy="0 0 0"/>
        </joint>
 </robot>