ROS interface for the ProximityRayPlugin plugin. More...
#include <ROSProximityRayPlugin.hh>
Public Member Functions | |
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. More... | |
virtual void | OnNewLaserScans () |
Update callback. More... | |
ROSProximityRayPlugin () | |
Constructor. More... | |
virtual | ~ROSProximityRayPlugin () |
Destructor. More... | |
Public Member Functions inherited from gazebo::ProximityRayPlugin | |
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. More... | |
virtual bool | ProcessScan () |
Process the scan data and update state. More... | |
ProximityRayPlugin () | |
Constructor. More... | |
virtual | ~ProximityRayPlugin () |
Destructor. More... | |
Protected Attributes | |
std::string | frameId |
for setting ROS frame id More... | |
event::ConnectionPtr | newLaserScansConnection |
The connection tied to ROSProximityRayPlugin::OnNewLaserScans() More... | |
std::string | robotNamespace |
for setting ROS namespace More... | |
ros::NodeHandle * | rosnode |
A pointer to the ROS node. A node will be instantiated if it does not exist. More... | |
osrf_gear::Proximity | state_msg |
ROS message for the sensor state. More... | |
ros::Publisher | stateChangePub |
ROS publisher for the sensor state changes. More... | |
ros::Publisher | statePub |
ROS publisher for the sensor state. More... | |
Protected Attributes inherited from gazebo::ProximityRayPlugin | |
physics::LinkPtr | link |
Pointer to parent link. More... | |
std::mutex | mutex |
Mutex to protect interruptionMsg. More... | |
event::ConnectionPtr | newLaserScansConnection |
The connection tied to ProximityRayPlugin::OnNewLaserScans() More... | |
transport::NodePtr | node |
Pointer to this node for publishing. More... | |
bool | normallyOpen |
Whether or not the output function is normally open (default) or normally closed. More... | |
bool | objectDetected |
Sensor detection state. More... | |
sensors::RaySensorPtr | parentSensor |
The parent sensor. More... | |
double | sensingRangeMax |
Maximum sensing range in meters. More... | |
double | sensingRangeMin |
Minimum sensing range in meters. More... | |
transport::PublisherPtr | stateChangePub |
Publisher for the sensor state change. More... | |
std::string | stateChangeTopic |
Topic name for state change message. More... | |
msgs::Header | stateMsg |
State message. More... | |
transport::PublisherPtr | statePub |
Publisher for the sensor state. More... | |
std::string | stateTopic |
Topic name for state message. More... | |
bool | useLinkFrame |
Convert sensor ranges to parent link frame? More... | |
physics::WorldPtr | world |
Pointer to world. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from gazebo::ProximityRayPlugin | |
std::string | Topic (std::string topicName) const |
Generate a scoped topic name from a local one. More... | |
ROS interface for the ProximityRayPlugin plugin.
Definition at line 38 of file ROSProximityRayPlugin.hh.
ROSProximityRayPlugin::ROSProximityRayPlugin | ( | ) |
Constructor.
Definition at line 28 of file ROSProximityRayPlugin.cc.
|
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 |
Definition at line 39 of file ROSProximityRayPlugin.cc.
|
virtual |
Update callback.
Reimplemented from gazebo::ProximityRayPlugin.
Definition at line 95 of file ROSProximityRayPlugin.cc.
|
protected |
for setting ROS frame id
Definition at line 72 of file ROSProximityRayPlugin.hh.
|
protected |
The connection tied to ROSProximityRayPlugin::OnNewLaserScans()
Definition at line 54 of file ROSProximityRayPlugin.hh.
|
protected |
for setting ROS namespace
Definition at line 69 of file ROSProximityRayPlugin.hh.
|
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.
|
protected |
ROS message for the sensor state.
Definition at line 66 of file ROSProximityRayPlugin.hh.
|
protected |
ROS publisher for the sensor state changes.
Definition at line 63 of file ROSProximityRayPlugin.hh.
|
protected |
ROS publisher for the sensor state.
Definition at line 60 of file ROSProximityRayPlugin.hh.