#include <ros/callback_queue.h>#include <ros/advertise_options.h>#include <gazebo/Controller.hh>#include <gazebo/Param.hh>#include <gazebo/Time.hh>#include <ros/ros.h>#include "boost/thread/mutex.hpp"#include <sensor_msgs/Range.h>

Go to the source code of this file.
Classes | |
| class | gazebo::GazeboRosIr |
| Sick LMS 200 lase controller. More... | |
Namespaces | |
| namespace | gazebo |
Defines | |
| #define | USE_CBQ |
| ROS ir scan controller. | |
| #define USE_CBQ |
ROS ir scan controller.
<model:physical name="ir_model">
<body:empty name="ir_body_name">
<sensor:ir name="ir_sensor">
<origin>0.0 0.0 0.0</origin>
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
<displayRays>false</displayRays>
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
<updateRate>10.0</updateRate>
<controller:gazebo_ros_ir name="ros_ir_sensor_controller" plugin="libgazebo_ros_ir.so">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>ir_scan</topicName>
<frameName>ir_model</frameName>
<interface:ir name="ros_ir_sensor_iface" />
</controller:gazebo_ros_ir>
</sensor:ir>
</body:empty>
</model:phyiscal>
Definition at line 63 of file gazebo_ros_ir.h.