A Ray Sensor Plugin which makes it act as a proximity sensor. More...
#include <ProximityRayPlugin.hh>

Public Member Functions | |
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
| Load the plugin. | |
| virtual void | OnNewLaserScans () |
| Update callback. | |
| virtual bool | ProcessScan () |
| Process the scan data and update state. | |
| ProximityRayPlugin () | |
| Constructor. | |
| virtual | ~ProximityRayPlugin () |
| Destructor. | |
Protected Member Functions | |
| std::string | Topic (std::string topicName) const |
| Generate a scoped topic name from a local one. | |
Protected Attributes | |
| physics::LinkPtr | link |
| Pointer to parent link. | |
| std::mutex | mutex |
| Mutex to protect interruptionMsg. | |
| event::ConnectionPtr | newLaserScansConnection |
| The connection tied to ProximityRayPlugin::OnNewLaserScans() | |
| transport::NodePtr | node |
| Pointer to this node for publishing. | |
| bool | normallyOpen |
| Whether or not the output function is normally open (default) or normally closed. | |
| bool | objectDetected |
| Sensor detection state. | |
| sensors::RaySensorPtr | parentSensor |
| The parent sensor. | |
| double | sensingRangeMax |
| Maximum sensing range in meters. | |
| double | sensingRangeMin |
| Minimum sensing range in meters. | |
| transport::PublisherPtr | stateChangePub |
| Publisher for the sensor state change. | |
| std::string | stateChangeTopic |
| Topic name for state change message. | |
| msgs::Header | stateMsg |
| State message. | |
| transport::PublisherPtr | statePub |
| Publisher for the sensor state. | |
| std::string | stateTopic |
| Topic name for state message. | |
| bool | useLinkFrame |
| Convert sensor ranges to parent link frame? | |
| physics::WorldPtr | world |
| Pointer to world. | |
A Ray Sensor Plugin which makes it act as a proximity sensor.
Definition at line 34 of file ProximityRayPlugin.hh.
Constructor.
Definition at line 32 of file ProximityRayPlugin.cc.
| ProximityRayPlugin::~ProximityRayPlugin | ( | ) | [virtual] |
Destructor.
Definition at line 37 of file ProximityRayPlugin.cc.
| void ProximityRayPlugin::Load | ( | sensors::SensorPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) |
Load the plugin.
| take | in SDF root element |
Reimplemented in gazebo::ROSProximityRayPlugin.
Definition at line 56 of file ProximityRayPlugin.cc.
| void ProximityRayPlugin::OnNewLaserScans | ( | ) | [virtual] |
Update callback.
Reimplemented in gazebo::ROSProximityRayPlugin.
Definition at line 141 of file ProximityRayPlugin.cc.
| bool ProximityRayPlugin::ProcessScan | ( | ) | [virtual] |
Process the scan data and update state.
Definition at line 165 of file ProximityRayPlugin.cc.
| std::string ProximityRayPlugin::Topic | ( | std::string | topicName | ) | const [protected] |
Generate a scoped topic name from a local one.
| local | local topic name |
Definition at line 46 of file ProximityRayPlugin.cc.
physics::LinkPtr gazebo::ProximityRayPlugin::link [protected] |
Pointer to parent link.
Definition at line 91 of file ProximityRayPlugin.hh.
std::mutex gazebo::ProximityRayPlugin::mutex [protected] |
Mutex to protect interruptionMsg.
Definition at line 67 of file ProximityRayPlugin.hh.
The connection tied to ProximityRayPlugin::OnNewLaserScans()
Reimplemented in gazebo::ROSProximityRayPlugin.
Definition at line 103 of file ProximityRayPlugin.hh.
transport::NodePtr gazebo::ProximityRayPlugin::node [protected] |
Pointer to this node for publishing.
Definition at line 97 of file ProximityRayPlugin.hh.
bool gazebo::ProximityRayPlugin::normallyOpen [protected] |
Whether or not the output function is normally open (default) or normally closed.
Definition at line 88 of file ProximityRayPlugin.hh.
bool gazebo::ProximityRayPlugin::objectDetected [protected] |
Sensor detection state.
Definition at line 76 of file ProximityRayPlugin.hh.
sensors::RaySensorPtr gazebo::ProximityRayPlugin::parentSensor [protected] |
The parent sensor.
Definition at line 100 of file ProximityRayPlugin.hh.
double gazebo::ProximityRayPlugin::sensingRangeMax [protected] |
Maximum sensing range in meters.
Definition at line 85 of file ProximityRayPlugin.hh.
double gazebo::ProximityRayPlugin::sensingRangeMin [protected] |
Minimum sensing range in meters.
Definition at line 82 of file ProximityRayPlugin.hh.
transport::PublisherPtr gazebo::ProximityRayPlugin::stateChangePub [protected] |
Publisher for the sensor state change.
Reimplemented in gazebo::ROSProximityRayPlugin.
Definition at line 61 of file ProximityRayPlugin.hh.
Topic name for state change message.
Definition at line 73 of file ProximityRayPlugin.hh.
msgs::Header gazebo::ProximityRayPlugin::stateMsg [protected] |
State message.
Definition at line 64 of file ProximityRayPlugin.hh.
transport::PublisherPtr gazebo::ProximityRayPlugin::statePub [protected] |
Publisher for the sensor state.
Reimplemented in gazebo::ROSProximityRayPlugin.
Definition at line 58 of file ProximityRayPlugin.hh.
std::string gazebo::ProximityRayPlugin::stateTopic [protected] |
Topic name for state message.
Definition at line 70 of file ProximityRayPlugin.hh.
bool gazebo::ProximityRayPlugin::useLinkFrame [protected] |
Convert sensor ranges to parent link frame?
Definition at line 79 of file ProximityRayPlugin.hh.
physics::WorldPtr gazebo::ProximityRayPlugin::world [protected] |
Pointer to world.
Definition at line 94 of file ProximityRayPlugin.hh.