+
+ <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.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>
+
+ <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="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="gazebo_ros_control" filename="libgazebo_ros_control.so">
+ <robotNamespace>/</robotNamespace>
+ <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
+ </plugin>
+
+ <plugin name="imu_controller" filename="libgazebo_ros_imu.so">
+ <alwaysOn>true</alwaysOn>
+ <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" />