A plugin for a contact sensor on a kit tray. More...
#include <ROSAriacKitTrayPlugin.hh>

Public Member Functions | |
| std::string | DetermineModelType (const std::string &modelName) |
| Update the kit based on which models are in contact. More... | |
| KitTrayPlugin () | |
| Constructor. More... | |
| virtual void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
| Load the model plugin. More... | |
| virtual | ~KitTrayPlugin () |
| Destructor. More... | |
Public Member Functions inherited from gazebo::SideContactPlugin | |
| SideContactPlugin () | |
| Constructor. More... | |
| virtual | ~SideContactPlugin () |
| Destructor. More... | |
Protected Member Functions | |
| void | OnUpdate (const common::UpdateInfo &_info) |
| Callback that receives the world update event. More... | |
| void | ProcessContactingModels () |
| Update the kit based on which models are in contact. More... | |
| void | PublishKitMsg () |
| Publish the Kit ROS message. More... | |
Protected Member Functions inherited from gazebo::SideContactPlugin | |
| 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... | |
Protected Attributes | |
| ariac::Kit | currentKit |
| Kit which is currently on the tray. More... | |
| ros::Publisher | currentKitPub |
| Publisher for the kit state. More... | |
| ros::NodeHandle * | rosNode |
| ROS node handle. More... | |
| std::string | trayID |
| ID of tray. More... | |
Protected Attributes inherited from gazebo::SideContactPlugin | |
| 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 contact sensor on a kit tray.
Definition at line 38 of file ROSAriacKitTrayPlugin.hh.
| KitTrayPlugin::KitTrayPlugin | ( | ) |
Constructor.
Definition at line 28 of file ROSAriacKitTrayPlugin.cc.
|
virtual |
Destructor.
Definition at line 33 of file ROSAriacKitTrayPlugin.cc.
| std::string gazebo::KitTrayPlugin::DetermineModelType | ( | const std::string & | modelName | ) |
Update the kit based on which models are in contact.
|
virtual |
Load the model plugin.
| [in] | _model | Pointer to the model that loaded this plugin. |
| [in] | _sdf | SDF element that describes the plugin. |
Reimplemented from gazebo::SideContactPlugin.
Definition at line 41 of file ROSAriacKitTrayPlugin.cc.
|
protectedvirtual |
Callback that receives the world update event.
Reimplemented from gazebo::SideContactPlugin.
Definition at line 61 of file ROSAriacKitTrayPlugin.cc.
|
protected |
Update the kit based on which models are in contact.
Definition at line 79 of file ROSAriacKitTrayPlugin.cc.
|
protected |
Publish the Kit ROS message.
Definition at line 102 of file ROSAriacKitTrayPlugin.cc.
|
protected |
Kit which is currently on the tray.
Definition at line 64 of file ROSAriacKitTrayPlugin.hh.
|
protected |
Publisher for the kit state.
Definition at line 73 of file ROSAriacKitTrayPlugin.hh.
|
protected |
ROS node handle.
Definition at line 70 of file ROSAriacKitTrayPlugin.hh.
|
protected |
ID of tray.
Definition at line 67 of file ROSAriacKitTrayPlugin.hh.