18 #ifndef _ROS_CONVEYOR_BELT_PLUGIN_HH_    19 #define _ROS_CONVEYOR_BELT_PLUGIN_HH_    27 #include <osrf_gear/ConveyorBeltControl.h>    44     public: 
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
    50       osrf_gear::ConveyorBeltControl::Request &_req,
    51       osrf_gear::ConveyorBeltControl::Response &_res);
 
bool OnControlCommand(osrf_gear::ConveyorBeltControl::Request &_req, osrf_gear::ConveyorBeltControl::Response &_res)
Receives requests on the conveyor belt's topic. 
ROSConveyorBeltPlugin()
Constructor. 
ros::NodeHandle * rosnode_
ros node handle 
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin. 
std::string robotNamespace_
for setting ROS name space 
ros::ServiceServer controlService_
Receives service calls to control the conveyor belt. 
ROS implementation of the ConveyorBeltPlugin plugin. 
virtual ~ROSConveyorBeltPlugin()
Destructor. 
A plugin for a conveyor belt.