<robot name="wild_thumper" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="PI" value="3.1415926535897931" />
+ <material name="wtgrey">
+ <color rgba="0.5 0.5 0.5 0.5"/>
+ </material>
+ <material name="wtred">
+ <color rgba="1 0 0 1"/>
+ </material>
+ <material name="wtblack">
+ <color rgba="0 0 0 1"/>
+ </material>
+ <material name="wtgreen">
+ <color rgba="0 1 0 0.8"/>
+ </material>
+
<link name="base_footprint">
<visual>
<geometry>
<box size="0.28 0.31 0.000001"/>
</geometry>
- <material name="grey">
- <color rgba="0.5 0.5 0.5 0.5"/>
- </material>
+ <material name="wtgrey"/>
</visual>
</link>
<geometry>
<box size="0.041 0.028 0.002"/>
</geometry>
- <material name="red">
- <color rgba="1 0 0 1"/>
- </material>
+ <material name="wtred"/>
</visual>
</link>
<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>
+ <material name="wtblack"/>
</visual>
</link>
<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>
+ <material name="wtgreen"/>
</visual>
</link>
<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>
+ <material name="wtgreen"/>
</visual>
</link>
<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>
+ <material name="wtgreen"/>
+ </visual>
+ </link>
+
+ <link name="antenna">
+ <visual>
+ <geometry>
+ <cylinder radius="0.006" length="0.165"/>
+ </geometry>
+ <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">
<origin xyz="-0.115 0.0 -0.012" rpy="0 ${-175*PI/180} 0"/>
</joint>
+ <joint name="antenna_joint" type="fixed">
+ <parent link="mounting_plate"/>
+ <child link="antenna"/>
+ <origin xyz="0.011 0.05 0" rpy="0 0 0"/>
+ </joint>
+
<joint name="lidar_joint" type="fixed">
<parent link="mounting_plate"/>
<child link="lidar"/>
<gazebo reference="${pos}_${side}_wheel">
<mu1 value="1.0"/>
<mu2 value="0.2"/>
- <kp value="1000000.0" />
- <kd value="1.0" />
+ <kp value="1000000000000.0" />
+ <kd value="0.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">
</horizontal>
</scan>
<range>
- <min>0.15</min>
+ <min>0.20</min>
<max>16.0</max>
<resolution>0.01</resolution>
</range>