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

Public Member Functions | |
| void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
| Load the plugin. More... | |
| bool | OnCommand (osrf_gear::AGVControl::Request &_req, osrf_gear::AGVControl::Response &_res) |
| Receives requests on the conveyor belt's topic. More... | |
| ROSAGVPlugin () | |
| Constructor. More... | |
| virtual | ~ROSAGVPlugin () |
| Destructor. More... | |
Private Attributes | |
| std::string | agvName |
| Name of the AGV. More... | |
| gazebo::common::PoseAnimationPtr | anim |
| Robot animation. More... | |
| gazebo::physics::ModelPtr | model |
| Pointer to the model. More... | |
| std::string | robotNamespace |
| for setting ROS name space More... | |
| ros::NodeHandle * | rosnode |
| ros node handle More... | |
| ros::ServiceServer | rosService |
| Receives service calls for controlling the AGV. More... | |
| ros::ServiceClient | rosSubmitTrayClient |
| Client for submitting trays for inspection. More... | |
ROS implementation of the ConveyorBeltPlugin plugin.
Definition at line 31 of file ROSAGVPlugin.hh.
| ROSAGVPlugin::ROSAGVPlugin | ( | ) |
Constructor.
Definition at line 29 of file ROSAGVPlugin.cc.
|
virtual |
Destructor.
Definition at line 34 of file ROSAGVPlugin.cc.
| void ROSAGVPlugin::Load | ( | physics::ModelPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) |
Load the plugin.
| [in] | _parent | Pointer to the parent model |
| [in] | _sdf | Pointer to the SDF element of the plugin. |
Definition at line 40 of file ROSAGVPlugin.cc.
| bool ROSAGVPlugin::OnCommand | ( | osrf_gear::AGVControl::Request & | _req, |
| osrf_gear::AGVControl::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 115 of file ROSAGVPlugin.cc.
|
private |
Name of the AGV.
Definition at line 52 of file ROSAGVPlugin.hh.
|
private |
Robot animation.
Definition at line 67 of file ROSAGVPlugin.hh.
|
private |
Pointer to the model.
Definition at line 70 of file ROSAGVPlugin.hh.
|
private |
for setting ROS name space
Definition at line 55 of file ROSAGVPlugin.hh.
|
private |
ros node handle
Definition at line 58 of file ROSAGVPlugin.hh.
|
private |
Receives service calls for controlling the AGV.
Definition at line 61 of file ROSAGVPlugin.hh.
|
private |
Client for submitting trays for inspection.
Definition at line 64 of file ROSAGVPlugin.hh.