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