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