18 #ifndef GAZEBO_ROS_ARIAC_TASK_MANAGER_PLUGIN_HH_ 19 #define GAZEBO_ROS_ARIAC_TASK_MANAGER_PLUGIN_HH_ 22 #include <gazebo/common/Plugin.hh> 23 #include <gazebo/physics/PhysicsTypes.hh> 24 #include <osrf_gear/SubmitTray.h> 26 #include <std_msgs/String.h> 27 #include <std_srvs/Trigger.h> 32 class ROSAriacTaskManagerPluginPrivate;
118 public:
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
121 protected:
void OnUpdate();
124 protected:
void ProcessGoalsToAnnounce();
127 protected:
void ControlConveyorBelt(
double velocity);
130 protected:
void PopulateConveyorBelt();
133 public:
bool HandleStartService(
134 std_srvs::Trigger::Request & req, std_srvs::Trigger::Response & res);
137 public:
bool HandleSubmitTrayService(
138 osrf_gear::SubmitTray::Request & req, osrf_gear::SubmitTray::Response & res);
141 protected:
void AssignGoal(
const ariac::Goal & goal);
144 protected:
void StopCurrentGoal();
147 private: std::unique_ptr<ROSAriacTaskManagerPluginPrivate>
dataPtr;
Class to store information about a goal.
std::unique_ptr< ROSAriacTaskManagerPluginPrivate > dataPtr
Private data pointer.
A plugin that orchestrates an ARIAC task. First of all, it loads a description of the goals...