<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">
<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">