17 #ifndef ROS_AGV_PLUGIN_HH_ 18 #define ROS_AGV_PLUGIN_HH_ 21 #include <gazebo/physics/physics.hh> 22 #include <gazebo/common/Plugin.hh> 26 #include <osrf_gear/AGVControl.h> 42 public:
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
48 osrf_gear::AGVControl::Request &_req,
49 osrf_gear::AGVControl::Response &_res);
67 private: gazebo::common::PoseAnimationPtr
anim;
70 private: gazebo::physics::ModelPtr
model;
ros::ServiceServer rosService
Receives service calls for controlling the AGV.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
gazebo::common::PoseAnimationPtr anim
Robot animation.
bool OnCommand(osrf_gear::AGVControl::Request &_req, osrf_gear::AGVControl::Response &_res)
Receives requests on the conveyor belt's topic.
ROS implementation of the ConveyorBeltPlugin plugin.
virtual ~ROSAGVPlugin()
Destructor.
ros::ServiceClient rosSubmitTrayClient
Client for submitting trays for inspection.
std::string agvName
Name of the AGV.
ROSAGVPlugin()
Constructor.
ros::NodeHandle * rosnode
ros node handle
gazebo::physics::ModelPtr model
Pointer to the model.
std::string robotNamespace
for setting ROS name space