A plugin for a conveyor belt. More...
#include <ConveyorBeltPlugin.hh>

| Public Member Functions | |
| ConveyorBeltPlugin () | |
| Constructor.  More... | |
| virtual void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) | 
| Load the model plugin.  More... | |
| void | SetVelocity (double velocity) | 
| Set the state of the conveyor belt.  More... | |
| virtual | ~ConveyorBeltPlugin () | 
| Destructor.  More... | |
|  Public Member Functions inherited from gazebo::SideContactPlugin | |
| SideContactPlugin () | |
| Constructor.  More... | |
| virtual | ~SideContactPlugin () | 
| Destructor.  More... | |
| Protected Member Functions | |
| void | ActOnContactingLinks (double velocity) | 
| Act on links that are ontop of the belt.  More... | |
| void | OnControlCommand (ConstHeaderPtr &_msg) | 
| Callback for responding to control commands.  More... | |
| void | OnUpdate (const common::UpdateInfo &_info) | 
| Callback that receives the world update event.  More... | |
| std::string | Topic (std::string topicName) const | 
| Generate a scoped topic name from a local one.  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 | |
| double | beltVelocity | 
| Belt velocity (m/s)  More... | |
| transport::SubscriberPtr | controlCommandSub | 
| Subscriber for the control commands.  More... | |
| std::mutex | mutex | 
| Mutex to protect the belt velocity.  More... | |
| transport::NodePtr | node | 
| Pointer to this node for publishing/subscribing.  More... | |
| ignition::math::Vector3d | velocityAxis | 
| Axis for belt velocity in local frame (+Y by default)  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 conveyor belt.
Definition at line 35 of file ConveyorBeltPlugin.hh.
| ConveyorBeltPlugin::ConveyorBeltPlugin | ( | ) | 
Constructor.
Definition at line 29 of file ConveyorBeltPlugin.cc.
| 
 | virtual | 
Destructor.
Definition at line 34 of file ConveyorBeltPlugin.cc.
| 
 | protected | 
Act on links that are ontop of the belt.
Definition at line 107 of file ConveyorBeltPlugin.cc.
| 
 | 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.
Reimplemented in gazebo::ROSConveyorBeltPlugin.
Definition at line 52 of file ConveyorBeltPlugin.cc.
| 
 | protected | 
Callback for responding to control commands.
Definition at line 120 of file ConveyorBeltPlugin.cc.
| 
 | protectedvirtual | 
Callback that receives the world update event.
Reimplemented from gazebo::SideContactPlugin.
Definition at line 93 of file ConveyorBeltPlugin.cc.
| void ConveyorBeltPlugin::SetVelocity | ( | double | velocity | ) | 
Set the state of the conveyor belt.
Definition at line 128 of file ConveyorBeltPlugin.cc.
| 
 | protected | 
Generate a scoped topic name from a local one.
| local | local topic name | 
Definition at line 42 of file ConveyorBeltPlugin.cc.
| 
 | protected | 
Belt velocity (m/s)
Definition at line 64 of file ConveyorBeltPlugin.hh.
| 
 | protected | 
Subscriber for the control commands.
Definition at line 55 of file ConveyorBeltPlugin.hh.
| 
 | protected | 
Mutex to protect the belt velocity.
Definition at line 67 of file ConveyorBeltPlugin.hh.
| 
 | protected | 
Pointer to this node for publishing/subscribing.
Definition at line 52 of file ConveyorBeltPlugin.hh.
| 
 | protected | 
Axis for belt velocity in local frame (+Y by default)
Definition at line 61 of file ConveyorBeltPlugin.hh.