Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::SideContactPlugin Class Reference

A plugin for a model with a contact sensor that only monitors collisions on one of its sides. More...

#include <SideContactPlugin.hh>

Inheritance diagram for gazebo::SideContactPlugin:
Inheritance graph
[legend]

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...
 

Detailed Description

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 & Destructor Documentation

SideContactPlugin::SideContactPlugin ( )

Constructor.

Definition at line 28 of file SideContactPlugin.cc.

SideContactPlugin::~SideContactPlugin ( )
virtual

Destructor.

Definition at line 33 of file SideContactPlugin.cc.

Member Function Documentation

void SideContactPlugin::CalculateContactingLinks ( )
protectedvirtual

Determine which links are in contact with the side of the parent link.

Definition at line 145 of file SideContactPlugin.cc.

void SideContactPlugin::CalculateContactingModels ( )
protectedvirtual

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.

Returns
true if the sensor was successfully found and is a contact sensor

Definition at line 106 of file SideContactPlugin.cc.

void SideContactPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
virtual

Load the sensor plugin.

Parameters
[in]_sensorPointer to the sensor that loaded this plugin.
[in]_sdfSDF 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)
protectedvirtual

Callback that recieves the contact sensor's messages.

Definition at line 131 of file SideContactPlugin.cc.

void SideContactPlugin::OnUpdate ( const common::UpdateInfo &  _info)
protectedvirtual

Called when world update events are received.

Parameters
[in]_infoUpdate information provided by the server.

Reimplemented in gazebo::KitTrayPlugin, gazebo::ConveyorBeltPlugin, and gazebo::ObjectDisposalPlugin.

Definition at line 139 of file SideContactPlugin.cc.

Member Data Documentation

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.

std::string gazebo::SideContactPlugin::contactSensorName
protected

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
mutableprotected

Mutex for protecting contacts msg.

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.

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.

std::string gazebo::SideContactPlugin::scopedContactSensorName
protected

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.

event::ConnectionPtr gazebo::SideContactPlugin::updateConnection
protected

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.


The documentation for this class was generated from the following files:


osrf_gear
Author(s):
autogenerated on Wed Sep 7 2016 03:48:13