]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - urdf/wild_thumper.urdf.xacro
added gazebo simulation
[ros_wild_thumper.git] / urdf / wild_thumper.urdf.xacro
index c783cffff36792da7c39d78102995dd0bf82f1a5..cf2c67240b9edfe7806f2ac61bb31149f23216da 100644 (file)
@@ -1,26 +1,34 @@
 <?xml version="1.0"?>
-<robot name="r2" xmlns:xacro="http://ros.org/wiki/xacro">
+<robot name="wild_thumper" xmlns:xacro="http://ros.org/wiki/xacro">
        <xacro:property name="PI" value="3.1415926535897931" />
        <xacro:include filename="$(find hector_sensors_description)/urdf/asus_camera.urdf.xacro" />
 
-       <link name="base_link">
+       <link name="base_footprint">
                <visual>
-                       <origin xyz="0.09 -0.02 0.07" rpy="${PI} 0 ${-PI/2}"/>
                        <geometry>
-                               <mesh filename="package://wild_thumper/meshes/wild_thumper_assembly_corrected.stl" scale="0.001 0.001 0.001" />
+                               <box size="0.28 0.31 0.0"/>
                        </geometry>
+                       <material name="grey">
+                               <color rgba="0.5 0.5 0.5 0.5"/>
+                       </material>
                </visual>
        </link>
 
-       <link name="base_footprint">
+       <link name="base_link">
+               <collision>
+                       <geometry>
+                               <box size="0.23 0.18 0.09"/>
+                       </geometry>
+               </collision>
                <visual>
                        <geometry>
-                               <box size="0.28 0.31 0.0"/>
+                               <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
                        </geometry>
-                       <material name="grey">
-                               <color rgba="0.5 0.5 0.5 0.5"/>
-                       </material>
                </visual>
+               <inertial>
+                       <mass value="1.9"/>
+                       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
+               </inertial>
        </link>
 
        <link name="base_imu_link">
                </visual>
        </link>
 
-       <xacro:asus_camera name="camera" parent="base_link">
+       <link name="mounting_plate">
+               <visual>
+                       <geometry>
+                               <box size="0.23 0.12 0.001"/>
+                       </geometry>
+               </visual>
+       </link>
+
+       <xacro:asus_camera name="camera" parent="mounting_plate">
                <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
        </xacro:asus_camera>
 
-       <joint name="imu_joint" type="fixed">
+       <link name="sonar_forward">
+               <visual>
+                       <geometry>
+                               <box size="0.016 0.044 0.02"/>
+                       </geometry>
+                       <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
+                       <material name="green">
+                               <color rgba="0 1 0 0.8"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="sonar_backward">
+               <visual>
+                       <geometry>
+                               <box size="0.016 0.044 0.02"/>
+                       </geometry>
+                       <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
+                       <material name="green">
+                               <color rgba="0 1 0 0.8"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="ir_left">
+               <visual>
+                       <geometry>
+                               <box size="0.015 0.015 0.046"/>
+                       </geometry>
+                       <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="ir_right">
+               <visual>
+                       <geometry>
+                               <box size="0.015 0.015 0.046"/>
+                       </geometry>
+                       <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <joint name="base_link_joint" type="fixed">
+               <parent link="base_footprint"/>
+               <child link="base_link"/>
+               <origin xyz="0.0 0.0 0.082" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="mounting_plate_joint" type="fixed">
                <parent link="base_link"/>
+               <child link="mounting_plate"/>
+               <origin xyz="0.0 0.0 0.044" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="imu_joint" type="fixed">
+               <parent link="mounting_plate"/>
                <child link="base_imu_link"/>
                <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
        </joint>
 
-       <joint name="base_link_joint" type="fixed">
-               <parent link="base_footprint"/>
-               <child link="base_link"/>
-               <origin xyz="0.0 0.0 0.13" rpy="0 0 0"/>
+       <joint name="sonar_forward_joint" type="fixed">
+               <parent link="mounting_plate"/>
+               <child link="sonar_forward"/>
+               <origin xyz="0.115 0.0 -0.012" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="sonar_backward_joint" type="fixed">
+               <parent link="mounting_plate"/>
+               <child link="sonar_backward"/>
+               <origin xyz="-0.115 0.0 -0.012" rpy="0 ${PI} 0"/>
        </joint>
+
+       <joint name="ir_left_joint" type="fixed">
+               <parent link="mounting_plate"/>
+               <child link="ir_left"/>
+               <origin xyz="0.0 ${0.072+0.015} -0.045" rpy="0 0 ${PI/2}"/>
+       </joint>
+
+       <joint name="ir_right_joint" type="fixed">
+               <parent link="mounting_plate"/>
+               <child link="ir_right"/>
+               <origin xyz="0.0 ${-0.072-0.015} -0.045" rpy="0 0 ${-PI/2}"/>
+       </joint>
+
+       <xacro:macro name="wheel" params="pos side xyz rpy">   
+               <link name="${pos}_${side}_wheel">
+                       <visual>
+                               <origin xyz="0 0 0" rpy="0 0 0"/>
+                               <geometry>
+                                       <mesh filename="package://wild_thumper/meshes/wheel_${side}.stl" />
+                               </geometry>
+                       </visual>
+                       <collision>
+                               <origin xyz="0 0 0" rpy="${-PI/2} 0 0"/>
+                               <geometry>
+                                       <cylinder radius="0.06" length="0.06"/>
+                               </geometry>
+                       </collision>
+                       <inertial>
+                               <origin xyz="0 0 0" rpy="0 0 0"/>
+                               <mass value="0.1"/>
+                               <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
+                       </inertial>
+               </link>
+               <joint name="${pos}_${side}_wheel_joint" type="continuous">
+                       <parent link="base_link"/>
+                       <child link="${pos}_${side}_wheel"/>
+                       <axis xyz="0 1 0"/>
+                       <origin xyz="${xyz}" rpy="${rpy}"/>
+               </joint>
+       </xacro:macro>
+
+       <gazebo reference="front_left_wheel">
+               <dampingFactor>0.001</dampingFactor>
+       </gazebo>
+       <gazebo reference="front_right_wheel">
+               <dampingFactor>0.001</dampingFactor>
+       </gazebo>
+
+       <xacro:wheel pos="aft" side="left"  xyz="-0.06398 0.11407 -0.022446" rpy="0 0 0" />
+       <xacro:wheel pos="aft" side="right" xyz="-0.07397 -0.11408 -0.022446" rpy="0 0 0" />
+       <xacro:wheel pos="front" side="left"  xyz="0.07602 0.11407 -0.022446" rpy="0 0 0" />
+       <xacro:wheel pos="front" side="right" xyz="0.07397 -0.11408 -0.022446" rpy="0 0 0" />
+
+       <gazebo>
+               <plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
+                       <robotNamespace>/</robotNamespace>
+                       <jointName>aft_left_wheel_joint, aft_right_wheel_joint, front_left_wheel_joint, front_right_wheel_joint</jointName>
+                       <updateRate>10.0</updateRate>
+                       <alwaysOn>true</alwaysOn>
+               </plugin>
+
+               <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
+                       <robotNamespace>/</robotNamespace>
+                       <alwaysOn>true</alwaysOn>
+                       <updateRate>10.0</updateRate>
+                       <leftJoint>aft_right_wheel_joint</leftJoint>
+                       <rightJoint>aft_left_wheel_joint</rightJoint>
+                       <wheelSeparation>0.252</wheelSeparation>
+                       <wheelDiameter>0.12</wheelDiameter>
+                       <wheelTorque>5.0</wheelTorque>
+                       <commandTopic>cmd_vel</commandTopic>
+                       <odometryTopic>odom</odometryTopic>
+                       <odometryFrame>odom</odometryFrame>
+                       <robotBaseFrame>base_footprint</robotBaseFrame>
+                       <rosDebugLevel>Info</rosDebugLevel>
+                       <publishWheelTF>false</publishWheelTF>
+                       <publishWheelJointState>true</publishWheelJointState>
+                       <wheelAcceleration>0.0</wheelAcceleration>
+                       <odometrySource>world</odometrySource>
+                       <publishTf>true</publishTf>
+               </plugin>
+       </gazebo>
 </robot>