Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef GAZEBO_ROS_ARIAC_TASK_MANAGER_PLUGIN_HH_
00019 #define GAZEBO_ROS_ARIAC_TASK_MANAGER_PLUGIN_HH_
00020
00021 #include <memory>
00022 #include <gazebo/common/Plugin.hh>
00023 #include <gazebo/physics/PhysicsTypes.hh>
00024 #include <osrf_gear/SubmitTray.h>
00025 #include <sdf/sdf.hh>
00026 #include <std_msgs/String.h>
00027 #include <std_srvs/Trigger.h>
00028
00029 namespace gazebo
00030 {
00031
00032 class ROSAriacTaskManagerPluginPrivate;
00033
00109 class GAZEBO_VISIBLE ROSAriacTaskManagerPlugin : public WorldPlugin
00110 {
00112 public: ROSAriacTaskManagerPlugin();
00113
00115 public: virtual ~ROSAriacTaskManagerPlugin();
00116
00117
00118 public: virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
00119
00121 protected: void OnUpdate();
00122
00124 protected: void ProcessGoalsToAnnounce();
00125
00127 protected: void ControlConveyorBelt(double velocity);
00128
00130 protected: void PopulateConveyorBelt();
00131
00133 public: bool HandleStartService(
00134 std_srvs::Trigger::Request & req, std_srvs::Trigger::Response & res);
00135
00137 public: bool HandleSubmitTrayService(
00138 osrf_gear::SubmitTray::Request & req, osrf_gear::SubmitTray::Response & res);
00139
00141 protected: void AssignGoal(const ariac::Goal & goal);
00142
00144 protected: void StopCurrentGoal();
00145
00147 private: std::unique_ptr<ROSAriacTaskManagerPluginPrivate> dataPtr;
00148 };
00149 }
00150 #endif