Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef ROS_AGV_PLUGIN_HH_
00018 #define ROS_AGV_PLUGIN_HH_
00019
00020 #include <sdf/sdf.hh>
00021 #include <gazebo/physics/physics.hh>
00022 #include <gazebo/common/Plugin.hh>
00023
00024
00025 #include <ros/ros.h>
00026 #include <osrf_gear/AGVControl.h>
00027
00028 namespace gazebo
00029 {
00031 class ROSAGVPlugin : public ModelPlugin
00032 {
00034 public: ROSAGVPlugin();
00035
00037 public: virtual ~ROSAGVPlugin();
00038
00042 public: void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
00043
00047 public: bool OnCommand(
00048 osrf_gear::AGVControl::Request &_req,
00049 osrf_gear::AGVControl::Response &_res);
00050
00052 private: std::string agvName;
00053
00055 private: std::string robotNamespace;
00056
00058 private: ros::NodeHandle *rosnode;
00059
00061 private: ros::ServiceServer rosService;
00062
00064 private: ros::ServiceClient rosSubmitTrayClient;
00065
00067 private: gazebo::common::PoseAnimationPtr anim;
00068
00070 private: gazebo::physics::ModelPtr model;
00071 };
00072 }
00073 #endif