<?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="2.5"/>
+ <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>
+
+ <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">
+ <hardwareInterface>VelocityJointInterface</hardwareInterface>
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+ </xacro:macro>
+
+ <xacro:wheel pos="rear" side="left" xyz="-0.06398 0.114 -0.022446" rpy="0 0 0" />
+ <xacro:wheel pos="rear" side="right" xyz="-0.07397 -0.114 -0.022446" rpy="0 0 0" />
+ <xacro:wheel pos="front" side="left" xyz="0.07602 0.114 -0.022446" rpy="0 0 0" />
+ <xacro:wheel pos="front" side="right" xyz="0.07397 -0.114 -0.022446" rpy="0 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>
+ </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="6" fov="${30*PI/180}" radiation="ultrasound" />
+ <xacro:range_sensor name="sonar_backward" ros_topic="range_backward" update_rate="10" minRange="0.04" maxRange="6" fov="${30*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>