44     ROS_FATAL_STREAM(
"A ROS node for Gazebo has not been initialized, unable to load plugin. "    45       << 
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
    53   if (_sdf->HasElement(
"robotNamespace"))
    55     this->
robotNamespace = _sdf->GetElement(
"robotNamespace")->Get<std::string>() + 
"/";
    60   if (_sdf->HasElement(
"output_state_topic"))
    62     this->stateTopic = _sdf->Get<std::string>(
"output_state_topic");
    66   if (_sdf->HasElement(
"output_change_topic"))
    68     this->stateChangeTopic = _sdf->Get<std::string>(
"output_change_topic");
    71   this->
frameId = _parent->Name() + 
"_frame";
    72   if (_sdf->HasElement(
"frame_id"))
    74     this->frameId = _sdf->Get<std::string>(
"frame_id");
    97   auto now = this->
world->GetSimTime();
    99   this->
state_msg.header.stamp.sec = now.sec;
   100   this->
state_msg.header.stamp.nsec = now.nsec;
   107     gzdbg << this->
parentSensor->Name() << 
": change in sensor state\n";
 virtual void OnNewLaserScans()
Update callback. 
osrf_gear::Proximity state_msg
ROS message for the sensor state. 
ROS interface for the ProximityRayPlugin plugin. 
void publish(const boost::shared_ptr< M > &message) const 
ROSCPP_DECL bool isInitialized()
physics::WorldPtr world
Pointer to world. 
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin. 
virtual bool ProcessScan()
Process the scan data and update state. 
event::ConnectionPtr newLaserScansConnection
The connection tied to ROSProximityRayPlugin::OnNewLaserScans() 
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin. 
virtual ~ROSProximityRayPlugin()
Destructor. 
std::string frameId
for setting ROS frame id 
ros::Publisher stateChangePub
ROS publisher for the sensor state changes. 
#define ROS_FATAL_STREAM(args)
double sensingRangeMin
Minimum sensing range in meters. 
bool objectDetected
Sensor detection state. 
sensors::RaySensorPtr parentSensor
The parent sensor. 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string stateTopic
Topic name for state message. 
ros::NodeHandle * rosnode
A pointer to the ROS node. A node will be instantiated if it does not exist. 
double sensingRangeMax
Maximum sensing range in meters. 
std::string stateChangeTopic
Topic name for state change message. 
ros::Publisher statePub
ROS publisher for the sensor state. 
std::string robotNamespace
for setting ROS namespace