]> defiant.homedns.org Git - ros_roboint.git/blobdiff - urdf/explorer.urdf
Migration to ros control (diff_drive_controller)
[ros_roboint.git] / urdf / explorer.urdf
index d5c84c594f2ee3e6b2bce8908637a95c3c2bf440..8f44ce2927fc3397b5d818b83261ec529b129600 100644 (file)
@@ -5,9 +5,9 @@
                        <geometry>
                                <box size="0.14 0.155 0.085"/>
                        </geometry>
-                       <origin xyz="0.06 0 0.0525" rpy="0 0 0"/>
-                       <material name="white">
-                               <color rgba="1 1 1 1"/>
+                       <origin xyz="0.0 0 0.0525" rpy="0 0 0"/>
+                       <material name="white_transparent">
+                               <color rgba="1 1 1 0.8"/>
                        </material>
                </visual>
        </link>
@@ -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>
                                <color rgba="0 0 0 1"/>
                        </material>
                </visual>
+               <collision>
+                       <geometry>
+                               <cylinder radius="0.026" length="0.02"/>
+                       </geometry>
+               </collision>
        </link>
 
        <link name="right_wheel">
                                <color rgba="0 0 0 1"/>
                        </material>
                </visual>
+               <collision>
+                       <geometry>
+                               <cylinder radius="0.026" length="0.02"/>
+                       </geometry>
+               </collision>
        </link>
 
        <link name="aft_wheel">
                </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>
+
+       <transmission name="left_wheel_trans" type="SimpleTransmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="left_wheel_joint">
+                       <hardwareInterface>VelocityJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="left_wheel_motor">
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
+
+       <transmission name="right_wheel_trans" type="SimpleTransmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="right_wheel_joint">
+                       <hardwareInterface>VelocityJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="right_wheel_motor">
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
 </robot>