]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - urdf/wild_thumper.urdf.xacro
fix some urdf inertias
[ros_wild_thumper.git] / urdf / wild_thumper.urdf.xacro
index 250efd306b9f11eb642d7db345ba8d1a957f9cdb..fd005afa5d7308fe564d8ab3d91d2489abc88414 100644 (file)
@@ -37,9 +37,9 @@
                        </geometry>
                </visual>
                <inertial>
-                       <origin xyz="-0.00275 0 -0.02" rpy="0 0 0"/>
+                       <origin xyz="-0.00275 0 0" rpy="0 0 0"/>
                        <mass value="2.5"/>
-                       <inertia ixx="0.012708" ixy="0.0" ixz="0.0" iyy="0.0084375" iyz="0.0" izz="0.017771"/>
+                       <inertia izz="0.014021" ixy="0.0" ixz="0.0" iyy="0.012708" iyz="0.0" ixx="0.0046875"/>
                </inertial>
        </link>
 
                        <origin xyz="0 0 0.0825" rpy="0 0 0"/>
                        <material name="wtblack"/>
                </visual>
+               <collision>
+                       <geometry>
+                               <cylinder radius="0.008" length="0.17"/>
+                       </geometry>
+                       <origin xyz="0 0 0.085" rpy="0 0 0"/>
+               </collision>
        </link>
 
        <joint name="base_link_joint" type="fixed">
        <joint name="antenna_joint" type="fixed">
                <parent link="mounting_plate"/>
                <child link="antenna"/>
-               <origin xyz="0.011 0.0588 0" rpy="0 0 0"/>
+               <origin xyz="0.011 0.05 0" rpy="0 0 0"/>
        </joint>
 
        <joint name="lidar_joint" type="fixed">
                        <mu1 value="1.0"/>
                        <mu2 value="0.2"/>
                        <kp value="1000000000000.0" />
-                       <kd value="0.0" />
+                       <kd value="1.0" />
                        <fdir1 value="0 1 0"/>
                        <minDepth>0.005</minDepth>
                </gazebo>
        <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">