]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - urdf/wild_thumper.urdf.xacro
Set sonar angle to 10° degree
[ros_wild_thumper.git] / urdf / wild_thumper.urdf.xacro
index cf2c67240b9edfe7806f2ac61bb31149f23216da..4630c878ec037fccda24432499ef8be9c7185c1d 100644 (file)
@@ -6,7 +6,7 @@
        <link name="base_footprint">
                <visual>
                        <geometry>
-                               <box size="0.28 0.31 0.0"/>
+                               <box size="0.28 0.31 0.000001"/>
                        </geometry>
                        <material name="grey">
                                <color rgba="0.5 0.5 0.5 0.5"/>
                        </geometry>
                </collision>
                <visual>
+                       <origin xyz="-0.00275 0 0" rpy="0 0 0"/>
                        <geometry>
                                <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
                        </geometry>
                </visual>
                <inertial>
-                       <mass value="1.9"/>
+                       <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"/>
                </inertial>
        </link>
                <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
        </xacro:asus_camera>
 
-       <link name="sonar_forward">
+       <link name="sonar_forward_left">
+               <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_forward_right">
                <visual>
                        <geometry>
                                <box size="0.016 0.044 0.02"/>
                <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
        </joint>
 
-       <joint name="sonar_forward_joint" type="fixed">
+       <joint name="sonar_forward_left_joint" type="fixed">
                <parent link="mounting_plate"/>
-               <child link="sonar_forward"/>
-               <origin xyz="0.115 0.0 -0.012" rpy="0 0 0"/>
+               <child link="sonar_forward_left"/>
+               <origin xyz="0.115 0.05 -0.012" rpy="0 ${-10*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"/>
        </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"/>
+               <origin xyz="-0.115 0.0 -0.012" rpy="0 ${-170*PI/180} 0"/>
        </joint>
 
        <joint name="ir_left_joint" type="fixed">
                        <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"/>
+                               <inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/>
                        </inertial>
                </link>
+
+               <gazebo reference="${pos}_${side}_wheel">
+                       <mu1 value="1.0"/>
+                       <mu2 value="1.0"/>
+                       <kp value="1000000.0" />
+                       <kd value="1.0" />
+                       <fdir1 value="1 0 0"/>
+               </gazebo>
+
                <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>
+               <transmission name="${pos}_${side}_wheel_trans" type="SimpleTransmission">
+                       <type>transmission_interface/SimpleTransmission</type>
+                       <joint name="${pos}_${side}_wheel_joint">
+                               <hardwareInterface>VelocityJointInterface</hardwareInterface>
+                       </joint>
+                       <actuator name="{pos}_${side}_wheel_motor">
+                               <mechanicalReduction>1</mechanicalReduction>
+                       </actuator>
+               </transmission>
+       </xacro:macro>
 
-       <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" />
+       <xacro:wheel pos="rear" side="left"   xyz="-0.07525  0.12 -0.025" rpy="${-5*PI/180} 0 0" />
+       <xacro:wheel pos="rear" side="right"  xyz="-0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
+       <xacro:wheel pos="front" side="left"  xyz=" 0.07525  0.12 -0.025" rpy="${-5*PI/180} 0 0" />
+       <xacro:wheel pos="front" side="right" xyz=" 0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
 
        <gazebo>
-               <plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
+               <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.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>
+                       <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
                </plugin>
 
-               <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
-                       <robotNamespace>/</robotNamespace>
+               <plugin name="imu_controller" filename="libgazebo_ros_imu.so">
                        <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>
+                       <updateRate>20.0</updateRate>
+                       <bodyName>base_imu_link</bodyName>
+                       <topicName>imu</topicName>
+                       <gaussianNoise>0.05</gaussianNoise>
+                       <frameName>base_imu_link</frameName>
+                       <xyzOffsets>0 0 0</xyzOffsets>
+                       <rpyOffset>0 0 0</rpyOffset>
+                       <serviceName>/default_imu</serviceName>
                </plugin>
        </gazebo>
+
+       <xacro:macro name="range_sensor" params="name ros_topic update_rate minRange maxRange fov radiation">
+               <gazebo reference="${name}">
+                       <sensor type="ray" name="${name}_sensor">
+                               <pose>0 0 0 0 0 0</pose>
+                               <update_rate>${update_rate}</update_rate>
+                               <visualize>false</visualize>
+                               <ray>
+                                       <scan>
+                                               <horizontal>
+                                                       <samples>5</samples>
+                                                       <resolution>1</resolution>
+                                                       <min_angle>-${fov/2}</min_angle>
+                                                       <max_angle>${fov/2}</max_angle>
+                                               </horizontal>
+                                               <vertical>
+                                                       <samples>5</samples>
+                                                       <resolution>1</resolution>
+                                                       <min_angle>-${fov/2}</min_angle>
+                                                       <max_angle>${fov/2}</max_angle>
+                                               </vertical>
+                                       </scan>
+                                       <range>
+                                               <min>${minRange}</min>
+                                               <max>${maxRange}</max>
+                                               <resolution>0.01</resolution>
+                                       </range>
+                               </ray>
+                               <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
+                                       <gaussianNoise>0.005</gaussianNoise>
+                                       <alwaysOn>true</alwaysOn>
+                                       <updateRate>${update_rate}</updateRate>
+                                       <topicName>${ros_topic}</topicName>
+                                       <frameName>${name}</frameName>
+                                       <fov>${fov}</fov>
+                                       <radiation>${radiation}</radiation>
+                               </plugin>
+                       </sensor>
+               </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_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" />
 </robot>