A plugin for a model with a contact sensor that only monitors collisions on one of its sides. More...
#include <SideContactPlugin.hh>

| Public Member Functions | |
| virtual void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) | 
| Load the sensor plugin.  More... | |
| SideContactPlugin () | |
| Constructor.  More... | |
| virtual | ~SideContactPlugin () | 
| Destructor.  More... | |
| Protected Member Functions | |
| virtual void | CalculateContactingLinks () | 
| Determine which links are in contact with the side of the parent link.  More... | |
| virtual void | CalculateContactingModels () | 
| Determine which models are in contact with the side of the parent link.  More... | |
| bool | FindContactSensor () | 
| Iterate through links of model to find sensor with the specified name.  More... | |
| virtual void | OnContactsReceived (ConstContactsPtr &_msg) | 
| Callback that recieves the contact sensor's messages.  More... | |
| virtual void | OnUpdate (const common::UpdateInfo &_info) | 
| Called when world update events are received.  More... | |
| Protected Attributes | |
| std::string | collisionName | 
| Name of the collision of the parent's link.  More... | |
| std::set< physics::LinkPtr > | contactingLinks | 
| Set of pointers to links that have collisions with the parent link's side.  More... | |
| std::set< physics::ModelPtr > | contactingModels | 
| Set of pointers to models that have collisions with the parent link's side.  More... | |
| std::string | contactSensorName | 
| Name of the contact sensor.  More... | |
| transport::SubscriberPtr | contactSub | 
| Subscriber for the contact topic.  More... | |
| physics::ModelPtr | model | 
| Pointer to the model.  More... | |
| boost::mutex | mutex | 
| Mutex for protecting contacts msg.  More... | |
| msgs::Contacts | newestContactsMsg | 
| Contacts msg received.  More... | |
| bool | newMsg | 
| Flag for new contacts message.  More... | |
| transport::NodePtr | node | 
| Pointer to this node for publishing/subscribing.  More... | |
| physics::LinkPtr | parentLink | 
| Pointer to the sensor's parent's link.  More... | |
| sensors::ContactSensorPtr | parentSensor | 
| Pointer to the contact sensor.  More... | |
| std::string | scopedContactSensorName | 
| Scoped name of the contact sensor.  More... | |
| ignition::math::Vector3d | sideNormal | 
| The normal, in local frame, to the side that is to have contacts monitored (default (0, 0, 1))  More... | |
| event::ConnectionPtr | updateConnection | 
| Pointer to the update event connection.  More... | |
| physics::WorldPtr | world | 
| Pointer to the world.  More... | |
A plugin for a model with a contact sensor that only monitors collisions on one of its sides.
Definition at line 35 of file SideContactPlugin.hh.
| SideContactPlugin::SideContactPlugin | ( | ) | 
Constructor.
Definition at line 28 of file SideContactPlugin.cc.
| 
 | virtual | 
Destructor.
Definition at line 33 of file SideContactPlugin.cc.
| 
 | protectedvirtual | 
Determine which links are in contact with the side of the parent link.
Definition at line 145 of file SideContactPlugin.cc.
| 
 | protectedvirtual | 
Determine which models are in contact with the side of the parent link.
Definition at line 189 of file SideContactPlugin.cc.
| 
 | protected | 
Iterate through links of model to find sensor with the specified name.
Definition at line 106 of file SideContactPlugin.cc.
| 
 | virtual | 
Load the sensor plugin.
| [in] | _sensor | Pointer to the sensor that loaded this plugin. | 
| [in] | _sdf | SDF element that describes the plugin. | 
Reimplemented in gazebo::KitTrayPlugin, gazebo::ConveyorBeltPlugin, gazebo::ObjectDisposalPlugin, and gazebo::ROSConveyorBeltPlugin.
Definition at line 41 of file SideContactPlugin.cc.
| 
 | protectedvirtual | 
Callback that recieves the contact sensor's messages.
Definition at line 131 of file SideContactPlugin.cc.
| 
 | protectedvirtual | 
Called when world update events are received.
| [in] | _info | Update information provided by the server. | 
Reimplemented in gazebo::KitTrayPlugin, gazebo::ConveyorBeltPlugin, and gazebo::ObjectDisposalPlugin.
Definition at line 139 of file SideContactPlugin.cc.
| 
 | protected | 
Name of the collision of the parent's link.
Definition at line 93 of file SideContactPlugin.hh.
| 
 | protected | 
Set of pointers to links that have collisions with the parent link's side.
Definition at line 99 of file SideContactPlugin.hh.
| 
 | protected | 
Set of pointers to models that have collisions with the parent link's side.
Definition at line 102 of file SideContactPlugin.hh.
| 
 | protected | 
Name of the contact sensor.
Definition at line 59 of file SideContactPlugin.hh.
| 
 | protected | 
Subscriber for the contact topic.
Definition at line 81 of file SideContactPlugin.hh.
| 
 | protected | 
Pointer to the model.
Definition at line 75 of file SideContactPlugin.hh.
| 
 | mutableprotected | 
Mutex for protecting contacts msg.
Definition at line 87 of file SideContactPlugin.hh.
| 
 | protected | 
Contacts msg received.
Definition at line 84 of file SideContactPlugin.hh.
| 
 | protected | 
Flag for new contacts message.
Definition at line 90 of file SideContactPlugin.hh.
| 
 | protected | 
Pointer to this node for publishing/subscribing.
Definition at line 78 of file SideContactPlugin.hh.
| 
 | protected | 
Pointer to the sensor's parent's link.
Definition at line 96 of file SideContactPlugin.hh.
| 
 | protected | 
Pointer to the contact sensor.
Definition at line 65 of file SideContactPlugin.hh.
| 
 | protected | 
Scoped name of the contact sensor.
Definition at line 62 of file SideContactPlugin.hh.
| 
 | protected | 
The normal, in local frame, to the side that is to have contacts monitored (default (0, 0, 1))
Definition at line 69 of file SideContactPlugin.hh.
| 
 | protected | 
Pointer to the update event connection.
Definition at line 56 of file SideContactPlugin.hh.
| 
 | protected | 
Pointer to the world.
Definition at line 72 of file SideContactPlugin.hh.