23 #ifndef _ROS_PROXIMITY_RAY_PLUGIN_HH_    24 #define _ROS_PROXIMITY_RAY_PLUGIN_HH_    28 #include <gazebo/physics/physics.hh>    29 #include <gazebo/common/Events.hh>    33 #include <osrf_gear/Proximity.h>    48     public: 
void Load( sensors::SensorPtr _parent, sdf::ElementPtr _sdf );
 virtual void OnNewLaserScans()
Update callback. 
osrf_gear::Proximity state_msg
ROS message for the sensor state. 
ROS interface for the ProximityRayPlugin plugin. 
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin. 
event::ConnectionPtr newLaserScansConnection
The connection tied to ROSProximityRayPlugin::OnNewLaserScans() 
virtual ~ROSProximityRayPlugin()
Destructor. 
ROSProximityRayPlugin()
Constructor. 
A Ray Sensor Plugin which makes it act as a proximity sensor. 
std::string frameId
for setting ROS frame id 
ros::Publisher stateChangePub
ROS publisher for the sensor state changes. 
ros::NodeHandle * rosnode
A pointer to the ROS node. A node will be instantiated if it does not exist. 
ros::Publisher statePub
ROS publisher for the sensor state. 
std::string robotNamespace
for setting ROS namespace