ROS interface for the ProximityRayPlugin plugin. More...
#include <ROSProximityRayPlugin.hh>
Public Member Functions | |
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. | |
virtual void | OnNewLaserScans () |
Update callback. | |
ROSProximityRayPlugin () | |
Constructor. | |
virtual | ~ROSProximityRayPlugin () |
Destructor. | |
Protected Attributes | |
std::string | frameId |
for setting ROS frame id | |
event::ConnectionPtr | newLaserScansConnection |
The connection tied to ROSProximityRayPlugin::OnNewLaserScans() | |
std::string | robotNamespace |
for setting ROS namespace | |
ros::NodeHandle * | rosnode |
A pointer to the ROS node. A node will be instantiated if it does not exist. | |
osrf_gear::Proximity | state_msg |
ROS message for the sensor state. | |
ros::Publisher | stateChangePub |
ROS publisher for the sensor state changes. | |
ros::Publisher | statePub |
ROS publisher for the sensor state. |
ROS interface for the ProximityRayPlugin plugin.
Definition at line 38 of file ROSProximityRayPlugin.hh.
Constructor.
Definition at line 28 of file ROSProximityRayPlugin.cc.
ROSProximityRayPlugin::~ROSProximityRayPlugin | ( | ) | [virtual] |
Destructor.
Definition at line 34 of file ROSProximityRayPlugin.cc.
void ROSProximityRayPlugin::Load | ( | sensors::SensorPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Load the plugin.
_parent | The parent entity must be a Ray sensor |
Reimplemented from gazebo::ProximityRayPlugin.
Definition at line 39 of file ROSProximityRayPlugin.cc.
void ROSProximityRayPlugin::OnNewLaserScans | ( | ) | [virtual] |
Update callback.
Reimplemented from gazebo::ProximityRayPlugin.
Definition at line 95 of file ROSProximityRayPlugin.cc.
std::string gazebo::ROSProximityRayPlugin::frameId [protected] |
for setting ROS frame id
Definition at line 72 of file ROSProximityRayPlugin.hh.
The connection tied to ROSProximityRayPlugin::OnNewLaserScans()
Reimplemented from gazebo::ProximityRayPlugin.
Definition at line 54 of file ROSProximityRayPlugin.hh.
for setting ROS namespace
Definition at line 69 of file ROSProximityRayPlugin.hh.
ros::NodeHandle* gazebo::ROSProximityRayPlugin::rosnode [protected] |
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition at line 57 of file ROSProximityRayPlugin.hh.
osrf_gear::Proximity gazebo::ROSProximityRayPlugin::state_msg [protected] |
ROS message for the sensor state.
Definition at line 66 of file ROSProximityRayPlugin.hh.
ROS publisher for the sensor state changes.
Reimplemented from gazebo::ProximityRayPlugin.
Definition at line 63 of file ROSProximityRayPlugin.hh.
ROS publisher for the sensor state.
Reimplemented from gazebo::ProximityRayPlugin.
Definition at line 60 of file ROSProximityRayPlugin.hh.