Public Member Functions | Protected Member Functions | Private Attributes
gazebo::ROSAriacTaskManagerPlugin Class Reference

A plugin that orchestrates an ARIAC task. First of all, it loads a description of the goals. Here's an example: More...

#include <ROSAriacTaskManagerPlugin.hh>

List of all members.

Public Member Functions

bool HandleStartService (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 Callback received when the team requests the competition start.
bool HandleSubmitTrayService (osrf_gear::SubmitTray::Request &req, osrf_gear::SubmitTray::Response &res)
 Callback for when a tray is submitted for inspection.
virtual void Load (physics::WorldPtr _world, sdf::ElementPtr _sdf)
 ROSAriacTaskManagerPlugin ()
 Constructor.
virtual ~ROSAriacTaskManagerPlugin ()
 Destructor.

Protected Member Functions

void AssignGoal (const ariac::Goal &goal)
 Assign a goal to be monitored by the scorer.
void ControlConveyorBelt (double velocity)
 Set the velocity of the conveyor belt.
void OnUpdate ()
 Update the plugin.
void PopulateConveyorBelt ()
 Start populating the conveyor belt.
void ProcessGoalsToAnnounce ()
 Decide whether to announce a new goal.
void StopCurrentGoal ()
 Stop scoring the current goal and assign the next goal on stack.

Private Attributes

std::unique_ptr
< ROSAriacTaskManagerPluginPrivate
dataPtr
 Private data pointer.

Detailed Description

A plugin that orchestrates an ARIAC task. First of all, it loads a description of the goals. Here's an example:

<goal> <time>5.0</time>

<kit> <object> <type>coke_can</type> <pose>-1 2.5 0.2 0 0 0</pose> </object> <object> <type>cordless_drill/</type> <pose>-1 2.5 0.2 0 0 0</pose> </object> <object> <type>beer</type> <pose>-1 2.5 0.2 0 0 0</pose> </object> </kit>

<kit> <object> <type>coke_can</type> <pose>-1 2.5 0.2 0 0 0</pose> </object> <object> <type>cordless_drill/</type> <pose>-1 2.5 0.2 0 0 0</pose> </object> <object> <type>beer</type> <pose>-1 2.5 0.2 0 0 0</pose> </object> </kit> </goal>

A task can have multiple goals. Each goal has a time element. At that point in simulation time, the goal will be notified to the team. A goal is composed by a positive number of kits. A kit is composed by a positive number of objects. An object contains a type (e.g.: coke_can) and a pose. The pose is the target pose where the object should be placed on a destination tray.

After loading the goals, the plugin will use a simple finite state machine to handle the different tasks to do.

The initial state is called "init" and there's not much to do when the plugin is in this state. The state of the Gazebo task manager is periodically published on a ROS topic "gazebo_task/state". This topic can be changed using the SDF element <gazebo_task_state_topic>. The plugin is waiting for a ROS message on topic "team_task/state". This topic shows the state of the team performing the task. When the value of a message received is "ready", the plugin will transition its internal state towards "ready" too.

The "ready" state is considered simulation time zero for notifying the goals to the teams. A <time>1.0</time> inside a <goal> element will be notified 1 second after entering in the "ready" state. The goal will be published using a ROS topic on the topic ${robot_namespace}/goal or ${robot_namespace}/${goals_topic} if the parameter <goals_topic> is passed in to the plugin. Also, when the plugin is in this state, it will use the conveyor activation topic to communicate with the Population plugin and enable the population of the conveyor belt. The element <conveyor_activation_topic> should match the topic used in the <activation_topic> of the Population plugin. After enabling the conveyor belt, the state changes to "go".

In "go" state, the plugin will be updating the function that processes the goals. This is essentially checking if it's time to announce a new goal. ToDo: Check if the team has completed all the goals or the maximum time limit has been reached. In that case, move to "finish" state.

In "finish" state there's nothing to do.

Definition at line 109 of file ROSAriacTaskManagerPlugin.hh.


Constructor & Destructor Documentation

Constructor.

Definition at line 160 of file ROSAriacTaskManagerPlugin.cc.

Destructor.

Definition at line 166 of file ROSAriacTaskManagerPlugin.cc.


Member Function Documentation

void ROSAriacTaskManagerPlugin::AssignGoal ( const ariac::Goal goal) [protected]

Assign a goal to be monitored by the scorer.

Definition at line 557 of file ROSAriacTaskManagerPlugin.cc.

void ROSAriacTaskManagerPlugin::ControlConveyorBelt ( double  velocity) [protected]

Set the velocity of the conveyor belt.

Definition at line 528 of file ROSAriacTaskManagerPlugin.cc.

bool ROSAriacTaskManagerPlugin::HandleStartService ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Callback received when the team requests the competition start.

Definition at line 485 of file ROSAriacTaskManagerPlugin.cc.

bool ROSAriacTaskManagerPlugin::HandleSubmitTrayService ( osrf_gear::SubmitTray::Request &  req,
osrf_gear::SubmitTray::Response &  res 
)

Callback for when a tray is submitted for inspection.

Definition at line 504 of file ROSAriacTaskManagerPlugin.cc.

void ROSAriacTaskManagerPlugin::Load ( physics::WorldPtr  _world,
sdf::ElementPtr  _sdf 
) [virtual]

Definition at line 172 of file ROSAriacTaskManagerPlugin.cc.

Update the plugin.

Definition at line 385 of file ROSAriacTaskManagerPlugin.cc.

Start populating the conveyor belt.

Definition at line 548 of file ROSAriacTaskManagerPlugin.cc.

Decide whether to announce a new goal.

Definition at line 465 of file ROSAriacTaskManagerPlugin.cc.

Stop scoring the current goal and assign the next goal on stack.

Definition at line 571 of file ROSAriacTaskManagerPlugin.cc.


Member Data Documentation

Private data pointer.

Definition at line 147 of file ROSAriacTaskManagerPlugin.hh.


The documentation for this class was generated from the following files:


osrf_gear
Author(s):
autogenerated on Mon Sep 5 2016 03:41:33