ROS implementation of the ConveyorBeltPlugin plugin. More...
#include <ROSConveyorBeltPlugin.hh>

Public Member Functions | |
| void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
| Load the plugin. More... | |
| bool | OnControlCommand (osrf_gear::ConveyorBeltControl::Request &_req, osrf_gear::ConveyorBeltControl::Response &_res) |
| Receives requests on the conveyor belt's topic. More... | |
| ROSConveyorBeltPlugin () | |
| Constructor. More... | |
| virtual | ~ROSConveyorBeltPlugin () |
| Destructor. More... | |
Public Member Functions inherited from gazebo::ConveyorBeltPlugin | |
| ConveyorBeltPlugin () | |
| Constructor. 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... | |
Public Attributes | |
| ros::ServiceServer | controlService_ |
| Receives service calls to control the conveyor belt. More... | |
Private Attributes | |
| std::string | robotNamespace_ |
| for setting ROS name space More... | |
| ros::NodeHandle * | rosnode_ |
| ros node handle More... | |
Additional Inherited Members | |
Protected Member Functions inherited from gazebo::ConveyorBeltPlugin | |
| 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 inherited from gazebo::ConveyorBeltPlugin | |
| 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... | |
ROS implementation of the ConveyorBeltPlugin plugin.
Definition at line 33 of file ROSConveyorBeltPlugin.hh.
| ROSConveyorBeltPlugin::ROSConveyorBeltPlugin | ( | ) |
Constructor.
Definition at line 26 of file ROSConveyorBeltPlugin.cc.
|
virtual |
Destructor.
Definition at line 31 of file ROSConveyorBeltPlugin.cc.
|
virtual |
Load the plugin.
| [in] | _parent | Pointer to the parent model |
| [in] | _sdf | Pointer to the SDF element of the plugin. |
Reimplemented from gazebo::ConveyorBeltPlugin.
Definition at line 37 of file ROSConveyorBeltPlugin.cc.
| bool ROSConveyorBeltPlugin::OnControlCommand | ( | osrf_gear::ConveyorBeltControl::Request & | _req, |
| osrf_gear::ConveyorBeltControl::Response & | _res | ||
| ) |
Receives requests on the conveyor belt's topic.
| [in] | _req | The desired state of the conveyor belt. |
| [in] | _res | If the service succeeded or not. |
Definition at line 69 of file ROSConveyorBeltPlugin.cc.
| ros::ServiceServer gazebo::ROSConveyorBeltPlugin::controlService_ |
Receives service calls to control the conveyor belt.
Definition at line 60 of file ROSConveyorBeltPlugin.hh.
|
private |
for setting ROS name space
Definition at line 54 of file ROSConveyorBeltPlugin.hh.
|
private |
ros node handle
Definition at line 57 of file ROSConveyorBeltPlugin.hh.