- <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" />
+ <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" />
+
+ <gazebo reference="lidar">
+ <sensor type="ray" name="head_rplidar_a2_sensor">
+ <pose>0 0 0 0 0 0</pose>
+ <visualize>false</visualize>
+ <update_rate>12</update_rate>
+ <ray>
+ <scan>
+ <horizontal>
+ <samples>360</samples>
+ <resolution>1</resolution>
+ <min_angle>-3.12413907051</min_angle>
+ <max_angle>3.14159274101</max_angle>
+ </horizontal>
+ </scan>
+ <range>
+ <min>0.20</min>
+ <max>16.0</max>
+ <resolution>0.01</resolution>
+ </range>
+ <noise>
+ <type>gaussian</type>
+ <mean>0.0</mean>
+ <stddev>0.01</stddev>
+ </noise>
+ </ray>
+ <plugin name="gazebo_ros_head_rplidar_a2_controller" filename="libgazebo_ros_laser.so">
+ <topicName>/scan</topicName>
+ <frameName>lidar</frameName>
+ </plugin>
+ </sensor>
+ </gazebo>