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