]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - urdf/wild_thumper.urdf.xacro
urdf fixes
[ros_wild_thumper.git] / urdf / wild_thumper.urdf.xacro
index 4630c878ec037fccda24432499ef8be9c7185c1d..f50da66a00d57acdc1b1e9dc43582523eeb45b9b 100644 (file)
@@ -1,7 +1,6 @@
 <?xml version="1.0"?>
 <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_footprint">
                <visual>
@@ -17,7 +16,7 @@
        <link name="base_link">
                <collision>
                        <geometry>
-                               <box size="0.23 0.18 0.09"/>
+                               <box size="0.23 0.12 0.09"/>
                        </geometry>
                </collision>
                <visual>
@@ -29,7 +28,7 @@
                <inertial>
                        <origin xyz="-0.00275 0 -0.02" rpy="0 0 0"/>
                        <mass value="2.5"/>
-                       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
+                       <inertia ixx="0.012708" ixy="0.0" ixz="0.0" iyy="0.0084375" iyz="0.0" izz="0.017771"/>
                </inertial>
        </link>
 
                </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>
+       <link name="lidar">
+               <visual>
+                       <geometry>
+                               <mesh filename="package://wild_thumper/meshes/rplidar_a2.stl" scale="0.001 0.001 0.001"/>
+                       </geometry>
+                       <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
 
        <link name="sonar_forward_left">
                <visual>
                </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"/>
        <joint name="sonar_forward_left_joint" type="fixed">
                <parent link="mounting_plate"/>
                <child link="sonar_forward_left"/>
-               <origin xyz="0.115 0.05 -0.012" rpy="0 ${-10*PI/180} 0"/>
+               <origin xyz="0.115 0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
        </joint>
 
        <joint name="sonar_forward_right_joint" type="fixed">
                <parent link="mounting_plate"/>
                <child link="sonar_forward_right"/>
-               <origin xyz="0.115 -0.05 -0.012" rpy="0 ${-10*PI/180} 0"/>
+               <origin xyz="0.115 -0.05 -0.012" rpy="0 ${-5*PI/180} 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 ${-170*PI/180} 0"/>
+               <origin xyz="-0.115 0.0 -0.012" rpy="0 ${-175*PI/180} 0"/>
        </joint>
 
-       <joint name="ir_left_joint" type="fixed">
+       <joint name="lidar_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}"/>
+               <child link="lidar"/>
+               <origin xyz="0.075 0.01 ${0.0408/2}" rpy="0 0 ${-110*PI/180}"/>
        </joint>
 
        <xacro:macro name="wheel" params="pos side xyz rpy">   
                                </geometry>
                        </visual>
                        <collision>
-                               <origin xyz="0 0 0" rpy="${-PI/2} 0 0"/>
+                               <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.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/>
+                               <mass value="0.2"/>
+                               <inertia ixx="0.00024" ixy="0" ixz="0" iyy="0.00036" iyz="0" izz="0.00024"/>
                        </inertial>
                </link>
 
                <gazebo reference="${pos}_${side}_wheel">
                        <mu1 value="1.0"/>
-                       <mu2 value="1.0"/>
+                       <mu2 value="0.2"/>
                        <kp value="1000000.0" />
                        <kd value="1.0" />
-                       <fdir1 value="1 0 0"/>
+                       <fdir1 value="0 1 0"/>
+                       <minDepth>0.005</minDepth>
                </gazebo>
 
                <joint name="${pos}_${side}_wheel_joint" type="continuous">
                </gazebo>
        </xacro:macro>
 
-       <xacro:range_sensor name="sonar_forward" ros_topic="range_forward" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
+       <xacro:range_sensor name="sonar_forward_left" ros_topic="range_forward_left" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
+       <xacro:range_sensor name="sonar_forward_right" ros_topic="range_forward_right" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
        <xacro:range_sensor name="sonar_backward" ros_topic="range_backward" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
        <xacro:range_sensor name="ir_left" ros_topic="range_left" update_rate="10" minRange="0.04" maxRange="0.3" fov="${5*PI/180}" radiation="infrared" />
        <xacro:range_sensor name="ir_right" ros_topic="range_right" update_rate="10" minRange="0.04" maxRange="0.3" fov="${5*PI/180}" radiation="infrared" />
+
+       <gazebo reference="lidar">
+               <sensor type="ray" name="head_rplidar_a2_sensor">
+                       <pose>0 0 0 0 0 0</pose>
+                       <visualize>false</visualize>
+                       <update_rate>12</update_rate>
+                       <ray>
+                               <scan>
+                                       <horizontal>
+                                               <samples>360</samples>
+                                               <resolution>1</resolution>
+                                               <min_angle>-3.12413907051</min_angle>
+                                               <max_angle>3.14159274101</max_angle>
+                                       </horizontal>
+                               </scan>
+                               <range>
+                                       <min>0.15</min>
+                                       <max>16.0</max>
+                                       <resolution>0.01</resolution>
+                               </range>
+                               <noise>
+                                       <type>gaussian</type>
+                                       <mean>0.0</mean>
+                                       <stddev>0.01</stddev>
+                               </noise>
+                       </ray>
+                       <plugin name="gazebo_ros_head_rplidar_a2_controller" filename="libgazebo_ros_laser.so">
+                               <topicName>/scan</topicName>
+                               <frameName>lidar</frameName>
+                       </plugin>
+               </sensor>
+       </gazebo>
 </robot>