ROSAriacTaskManagerPlugin.cc
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <algorithm>
19 #include <limits>
20 #include <mutex>
21 #include <ostream>
22 #include <string>
23 #include <vector>
24 #include <gazebo/common/Assert.hh>
25 #include <gazebo/common/Console.hh>
26 #include <gazebo/common/Events.hh>
27 #include <gazebo/math/Pose.hh>
28 #include <gazebo/msgs/gz_string.pb.h>
29 #include <gazebo/physics/PhysicsTypes.hh>
30 #include <gazebo/physics/World.hh>
31 #include <gazebo/transport/transport.hh>
32 #include <ros/ros.h>
33 #include <sdf/sdf.hh>
34 #include <std_msgs/Float32.h>
35 #include <std_msgs/String.h>
36 #include <std_srvs/Trigger.h>
37 
38 
39 #include "osrf_gear/ARIAC.hh"
41 #include "osrf_gear/AriacScorer.h"
42 #include <osrf_gear/ConveyorBeltControl.h>
43 #include <osrf_gear/ConveyorBeltState.h>
44 #include "osrf_gear/Goal.h"
45 #include "osrf_gear/Kit.h"
46 #include "osrf_gear/KitObject.h"
47 #include "osrf_gear/VacuumGripperState.h"
48 
49 namespace gazebo
50 {
54  {
56  public: physics::WorldPtr world;
57 
59  public: sdf::ElementPtr sdf;
60 
62  public: std::vector<ariac::Goal> goalsToAnnounce;
63 
66  public: std::stack<ariac::Goal> goalsInProgress;
67 
70 
73 
75  public: std::unique_ptr<ros::NodeHandle> rosnode;
76 
79 
82 
85 
88 
91 
94 
97 
99  public: transport::NodePtr node;
100 
102  public: transport::PublisherPtr populatePub;
103 
106 
108  public: event::ConnectionPtr connection;
109 
111  public: common::Time lastUpdateTime;
112 
114  public: common::Time gameStartTime;
115 
117  public: double timeSpentOnCurrentGoal;
118 
120  public: std::string currentState = "init";
121 
123  public: std::mutex mutex;
124  };
125 }
126 
127 using namespace gazebo;
128 
130 
131 static void fillGoalMsg(const ariac::Goal &_goal,
133  osrf_gear::Goal &_msgGoal)
134 {
135  _msgGoal.goal_id.data = _goal.goalID;
136  for (const auto item : _goal.kits)
137  {
138  osrf_gear::Kit msgKit;
139  msgKit.kit_type.data = item.first;
140  for (const auto &obj : item.second.objects)
141  {
142  osrf_gear::KitObject msgObj;
143  msgObj.type = obj.type;
144  msgObj.pose.position.x = obj.pose.pos.x;
145  msgObj.pose.position.y = obj.pose.pos.y;
146  msgObj.pose.position.z = obj.pose.pos.z;
147  msgObj.pose.orientation.x = obj.pose.rot.x;
148  msgObj.pose.orientation.y = obj.pose.rot.y;
149  msgObj.pose.orientation.z = obj.pose.rot.z;
150  msgObj.pose.orientation.w = obj.pose.rot.w;
151 
152  // Add the object to the kit.
153  msgKit.objects.push_back(msgObj);
154  }
155  _msgGoal.kits.push_back(msgKit);
156  }
157 }
158 
161  : dataPtr(new ROSAriacTaskManagerPluginPrivate)
162 {
163 }
164 
167 {
168  this->dataPtr->rosnode->shutdown();
169 }
170 
172 void ROSAriacTaskManagerPlugin::Load(physics::WorldPtr _world,
173  sdf::ElementPtr _sdf)
174 {
175  GZ_ASSERT(_world, "ROSAriacTaskManagerPlugin world pointer is NULL");
176  GZ_ASSERT(_sdf, "ROSAriacTaskManagerPlugin sdf pointer is NULL");
177  this->dataPtr->world = _world;
178  this->dataPtr->sdf = _sdf;
179 
180  std::string robotNamespace = "";
181  if (_sdf->HasElement("robot_namespace"))
182  {
183  robotNamespace = _sdf->GetElement(
184  "robot_namespace")->Get<std::string>() + "/";
185  }
186 
187  std::string teamStartServiceName = "start";
188  if (_sdf->HasElement("team_start_service_name"))
189  teamStartServiceName = _sdf->Get<std::string>("team_start_service_name");
190 
191  std::string gazeboTaskStateTopic = "competition_state";
192  if (_sdf->HasElement("gazebo_task_state_topic"))
193  gazeboTaskStateTopic = _sdf->Get<std::string>("gazebo_task_state_topic");
194 
195  std::string gazeboTaskScoreTopic = "current_score";
196  if (_sdf->HasElement("gazebo_task_score_topic"))
197  gazeboTaskScoreTopic = _sdf->Get<std::string>("gazebo_task_score_topic");
198 
199  std::string conveyorControlTopic = "conveyor/control";
200  if (_sdf->HasElement("conveyor_control_topic"))
201  conveyorControlTopic = _sdf->Get<std::string>("conveyor_control_topic");
202 
203  std::string populationActivateTopic = "populate_belt";
204  if (_sdf->HasElement("population_activate_topic"))
205  populationActivateTopic = _sdf->Get<std::string>("population_activate_topic");
206 
207  std::string goalsTopic = "orders";
208  if (_sdf->HasElement("goals_topic"))
209  goalsTopic = _sdf->Get<std::string>("goals_topic");
210 
211  std::string submitTrayServiceName = "submit_tray";
212  if (_sdf->HasElement("submit_tray_service_name"))
213  submitTrayServiceName = _sdf->Get<std::string>("submit_tray_service_name");
214 
215 
216  // Parse the goals.
217  sdf::ElementPtr goalElem = NULL;
218  if (_sdf->HasElement("goal"))
219  {
220  goalElem = _sdf->GetElement("goal");
221  }
222 
223  unsigned int goalCount = 0;
224  while (goalElem)
225  {
226  // Parse the start time.
227  if (!goalElem->HasElement("start_time"))
228  {
229  gzerr << "Unable to find <start_time> element in <goal>. Ignoring" << std::endl;
230  goalElem = goalElem->GetNextElement("goal");
231  continue;
232  }
233  sdf::ElementPtr startTimeElement = goalElem->GetElement("start_time");
234  double startTime = startTimeElement->Get<double>();
235 
236  // Parse the allowed completion time.
237  double allowedTime = std::numeric_limits<double>::infinity();
238  if (goalElem->HasElement("allowed_time"))
239  {
240  sdf::ElementPtr allowedTimeElement = goalElem->GetElement("allowed_time");
241  allowedTime = allowedTimeElement->Get<double>();
242  }
243 
244  // Parse the kits.
245  if (!goalElem->HasElement("kit"))
246  {
247  gzerr << "Unable to find <kit> element in <goal>. Ignoring" << std::endl;
248  goalElem = goalElem->GetNextElement("goal");
249  continue;
250  }
251 
252  // Store all kits for a goal.
253  std::map<std::string, ariac::Kit> kits;
254 
255  sdf::ElementPtr kitElem = goalElem->GetElement("kit");
256  while (kitElem)
257  {
258  // Check the validity of the kit.
259  if (!kitElem->HasElement("object"))
260  {
261  gzerr << "Unable to find <object> element in <kit>. Ignoring"
262  << std::endl;
263  kitElem = kitElem->GetNextElement("kit");
264  continue;
265  }
266 
267  ariac::Kit kit;
268 
269  // Parse the kit type.
270  ariac::KitType_t kitType;
271  if (kitElem->HasElement("kit_type"))
272  {
273  kitType = kitElem->Get<std::string>("kit_type");
274  }
275  kit.kitType = kitType;
276 
277  // Parse the objects inside the kit.
278  sdf::ElementPtr objectElem = kitElem->GetElement("object");
279  while (objectElem)
280  {
281  // Parse the object type.
282  if (!objectElem->HasElement("type"))
283  {
284  gzerr << "Unable to find <type> in object.\n";
285  objectElem = objectElem->GetNextElement("object");
286  continue;
287  }
288  sdf::ElementPtr typeElement = objectElem->GetElement("type");
289  std::string type = typeElement->Get<std::string>();
290 
291  // Parse the object pose (optional).
292  if (!objectElem->HasElement("pose"))
293  {
294  gzerr << "Unable to find <pose> in object.\n";
295  objectElem = objectElem->GetNextElement("object");
296  continue;
297  }
298  sdf::ElementPtr poseElement = objectElem->GetElement("pose");
299  math::Pose pose = poseElement->Get<math::Pose>();
300 
301  // Add the object to the kit.
302  ariac::KitObject obj = {type, pose};
303  kit.objects.push_back(obj);
304 
305  objectElem = objectElem->GetNextElement("object");
306  }
307 
308  // Add a new kit to the collection of kits.
309  kits[kitType] = kit;
310 
311  kitElem = kitElem->GetNextElement("kit");
312  }
313 
314  // Add a new goal.
315  ariac::GoalID_t goalID = "goal_" + std::to_string(goalCount++);
316  ariac::Goal goal = {goalID, startTime, allowedTime, kits, 0.0};
317  this->dataPtr->goalsToAnnounce.push_back(goal);
318 
319  goalElem = goalElem->GetNextElement("goal");
320  }
321 
322  // Sort the goals by their start times.
323  std::sort(this->dataPtr->goalsToAnnounce.begin(), this->dataPtr->goalsToAnnounce.end());
324 
325  // Debug output.
326  // gzdbg << "Goals:" << std::endl;
327  // for (auto goal : this->dataPtr->goalsToAnnounce)
328  // gzdbg << goal << std::endl;
329 
330  // Initialize ROS
331  this->dataPtr->rosnode.reset(new ros::NodeHandle(robotNamespace));
332 
334  {
336  }
337 
338  // Publisher for announcing new goals.
339  this->dataPtr->goalPub = this->dataPtr->rosnode->advertise<
340  osrf_gear::Goal>(goalsTopic, 1000, true); // latched=true
341 
342  // Publisher for announcing new state of Gazebo's task.
343  this->dataPtr->gazeboTaskStatePub = this->dataPtr->rosnode->advertise<
344  std_msgs::String>(gazeboTaskStateTopic, 1000);
345 
346  // Publisher for announcing the score of the game.
347  this->dataPtr->gazeboTaskScorePub = this->dataPtr->rosnode->advertise<
348  std_msgs::Float32>(gazeboTaskScoreTopic, 1000);
349 
350  // Service for starting the competition.
351  this->dataPtr->teamStartServiceServer =
352  this->dataPtr->rosnode->advertiseService(teamStartServiceName,
354 
355  // Service for submitting trays for inspection.
356  this->dataPtr->submitTrayServiceServer =
357  this->dataPtr->rosnode->advertiseService(submitTrayServiceName,
359 
360  // Client for the conveyor control commands.
361  this->dataPtr->conveyorControlClient =
362  this->dataPtr->rosnode->serviceClient<osrf_gear::ConveyorBeltControl>(
363  conveyorControlTopic);
364 
365  // Initialize Gazebo transport.
366  this->dataPtr->node = transport::NodePtr(new transport::Node());
367  this->dataPtr->node->Init();
368  this->dataPtr->populatePub =
369  this->dataPtr->node->Advertise<msgs::GzString>(populationActivateTopic);
370 
371  // Initialize the game scorer.
372  this->dataPtr->trayInfoSub = this->dataPtr->rosnode->subscribe(
373  "/ariac/trays", 10, &AriacScorer::OnTrayInfoReceived, &this->dataPtr->ariacScorer);
374  this->dataPtr->gripperStateSub = this->dataPtr->rosnode->subscribe(
375  "/ariac/gripper/state", 10, &AriacScorer::OnGripperStateReceived,
376  &this->dataPtr->ariacScorer);
377 
378  this->dataPtr->gameStartTime = this->dataPtr->world->GetSimTime();
379 
380  this->dataPtr->connection = event::Events::ConnectWorldUpdateEnd(
381  boost::bind(&ROSAriacTaskManagerPlugin::OnUpdate, this));
382 }
383 
386 {
387  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
388  auto currentSimTime = this->dataPtr->world->GetSimTime();
389 
390  double elapsedTime = (currentSimTime - this->dataPtr->lastUpdateTime).Double();
391  if (this->dataPtr->currentState == "ready")
392  {
393  this->dataPtr->gameStartTime = currentSimTime;
394  this->dataPtr->currentState = "go";
395 
396  this->ControlConveyorBelt(0.2);
397  this->PopulateConveyorBelt();
398  }
399  else if (this->dataPtr->currentState == "go")
400  {
401  // Update the goal manager.
402  this->ProcessGoalsToAnnounce();
403 
404  // Update the score.
405  this->dataPtr->ariacScorer.Update(elapsedTime);
406  auto gameScore = this->dataPtr->ariacScorer.GetGameScore();
407  if (gameScore.total() != this->dataPtr->currentGameScore.total())
408  {
409  ROS_DEBUG_STREAM("Current game score: " << gameScore.total());
410  this->dataPtr->currentGameScore = gameScore;
411  }
412 
413  if (!this->dataPtr->goalsInProgress.empty())
414  {
415  this->dataPtr->goalsInProgress.top().timeTaken += elapsedTime;
416  auto goalID = this->dataPtr->goalsInProgress.top().goalID;
417  // TODO: timing should probably be managed by the scorer but we want to use sim time
418  this->dataPtr->timeSpentOnCurrentGoal = this->dataPtr->goalsInProgress.top().timeTaken;
419 
420  // Check for completed goals.
421  bool goalCompleted = this->dataPtr->ariacScorer.IsCurrentGoalComplete();
422  if (goalCompleted)
423  {
424  ROS_INFO_STREAM("Order complete: " << goalID);
425  this->StopCurrentGoal();
426  }
427  else
428  {
429  // Check if the time limit for the current goal has been exceeded.
430  if (this->dataPtr->timeSpentOnCurrentGoal > this->dataPtr->goalsInProgress.top().allowedTime)
431  {
432  ROS_INFO_STREAM("Order timed out: " << goalID);
433  this->StopCurrentGoal();
434  }
435  }
436  }
437 
438  if (this->dataPtr->goalsInProgress.empty() && this->dataPtr->goalsToAnnounce.empty())
439  {
440  this->dataPtr->currentGameScore.totalProcessTime =
441  (currentSimTime - this->dataPtr->gameStartTime).Double();
442  this->dataPtr->currentState = "end_game";
443  }
444  }
445  else if (this->dataPtr->currentState == "end_game")
446  {
447  ROS_INFO_STREAM("No more orders to process. Final score: " << this->dataPtr->currentGameScore.total());
448  ROS_INFO_STREAM("Score breakdown:\n" << this->dataPtr->currentGameScore);
449  this->dataPtr->currentState = "done";
450  }
451 
452  // TODO: Publish at a lower frequency.
453  std_msgs::Float32 scoreMsg;
454  scoreMsg.data = this->dataPtr->currentGameScore.total();
455  this->dataPtr->gazeboTaskScorePub.publish(scoreMsg);
456 
457  std_msgs::String stateMsg;
458  stateMsg.data = this->dataPtr->currentState;
459  this->dataPtr->gazeboTaskStatePub.publish(stateMsg);
460 
461  this->dataPtr->lastUpdateTime = currentSimTime;
462 }
463 
466 {
467  if (this->dataPtr->goalsToAnnounce.empty())
468  return;
469 
470  // Check whether announce a new goal from the list.
471  auto elapsed = this->dataPtr->world->GetSimTime() - this->dataPtr->gameStartTime;
472  if (elapsed.Double() >= this->dataPtr->goalsToAnnounce.front().startTime)
473  {
474  auto goal = this->dataPtr->goalsToAnnounce.front();
475 
476  // Move goal to the 'in process' stack
477  this->dataPtr->goalsInProgress.push(ariac::Goal(goal));
478  this->dataPtr->goalsToAnnounce.erase(this->dataPtr->goalsToAnnounce.begin());
479 
480  this->AssignGoal(goal);
481  }
482 }
483 
486  std_srvs::Trigger::Request & req,
487  std_srvs::Trigger::Response & res)
488 {
489  (void)req;
490  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
491 
492  if (this->dataPtr->currentState == "init") {
493  this->dataPtr->currentState = "ready";
494  res.success = true;
495  res.message = "competition started successfully!";
496  return true;
497  }
498  res.success = false;
499  res.message = "cannot start if not in 'init' state";
500  return true;
501 }
502 
505  osrf_gear::SubmitTray::Request & req,
506  osrf_gear::SubmitTray::Response & res)
507 {
508  std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
509 
510  if (this->dataPtr->currentState != "go") {
511  ROS_ERROR("Competition is not running so trays cannot be submitted.");
512  return false;
513  }
514 
515  ariac::KitTray kitTray;
516  if (!this->dataPtr->ariacScorer.GetTrayById(req.tray_id.data, kitTray))
517  {
518  res.success = false;
519  return true;
520  }
521  kitTray.currentKit.kitType = req.kit_type.data;
522  res.success = true;
523  res.inspection_result = this->dataPtr->ariacScorer.SubmitTray(kitTray).total();
524  return true;
525 }
526 
529 {
530 
531  if (!this->dataPtr->conveyorControlClient.exists())
532  {
533  this->dataPtr->conveyorControlClient.waitForExistence();
534  }
535 
536  // Make a service call to set the velocity of the belt
537  osrf_gear::ConveyorBeltState controlMsg;
538  controlMsg.velocity = velocity;
539  osrf_gear::ConveyorBeltControl srv;
540  srv.request.state = controlMsg;
541  this->dataPtr->conveyorControlClient.call(srv);
542  if (!srv.response.success) {
543  ROS_ERROR_STREAM("Failed to control conveyor");
544  }
545 }
546 
549 {
550  // Publish a message on the activation_plugin of the PopulationPlugin.
551  gazebo::msgs::GzString msg;
552  msg.set_data("restart");
553  this->dataPtr->populatePub->Publish(msg);
554 }
555 
558 {
559  // Publish the goal to ROS topic
560  ROS_INFO_STREAM("Announcing order: " << goal.goalID);
561  osrf_gear::Goal goalMsg;
562  fillGoalMsg(goal, goalMsg);
563  this->dataPtr->goalPub.publish(goalMsg);
564 
565  // Assign the scorer the goal to monitor
566  gzdbg << "Assigning order: " << goal << std::endl;
567  this->dataPtr->ariacScorer.AssignGoal(goal);
568 }
569 
572 {
573  if (this->dataPtr->goalsInProgress.size())
574  {
575  ROS_INFO_STREAM("Stopping order: " << this->dataPtr->goalsInProgress.top().goalID);
576  this->dataPtr->goalsInProgress.pop();
577  this->dataPtr->ariacScorer.UnassignCurrentGoal(this->dataPtr->timeSpentOnCurrentGoal);
578  }
579 
580  if (this->dataPtr->goalsInProgress.size())
581  {
582  // Assign the previous goal to the scorer
583  auto goal = this->dataPtr->goalsInProgress.top();
584  ROS_INFO_STREAM("Restoring order: " << goal.goalID);
585  this->AssignGoal(goal);
586  }
587 }
void PopulateConveyorBelt()
Start populating the conveyor belt.
ros::ServiceClient conveyorControlClient
Client for controlling the conveyor.
msg
std::vector< KitObject > objects
A kit is composed of multiple objects.
Definition: ARIAC.hh:287
transport::PublisherPtr populatePub
Publisher for enabling the object population on the conveyor.
static void fillGoalMsg(const ariac::Goal &_goal, osrf_gear::Goal &_msgGoal)
void ProcessGoalsToAnnounce()
Decide whether to announce a new goal.
Class to store information about a goal.
Definition: ARIAC.hh:291
ariac::GameScore currentGameScore
The current game score.
GZ_REGISTER_WORLD_PLUGIN(ROSPopulationPlugin)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
std::unique_ptr< ros::NodeHandle > rosnode
ROS node handle.
std::unique_ptr< ROSAriacTaskManagerPluginPrivate > dataPtr
Private data pointer.
event::ConnectionPtr connection
Connection event.
ros::Publisher gazeboTaskScorePub
Publishes the game score total.
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
bool HandleSubmitTrayService(osrf_gear::SubmitTray::Request &req, osrf_gear::SubmitTray::Response &res)
Callback for when a tray is submitted for inspection.
common::Time lastUpdateTime
The time the last update was called.
void OnGripperStateReceived(const osrf_gear::VacuumGripperState &stateMsg)
Callback for receiving gripper state message.
ros::Subscriber gripperStateSub
ROS subscriber for the gripper state.
Kit currentKit
The current state of the kit on the tray.
Definition: AriacKitTray.h:45
ros::Subscriber trayInfoSub
ROS subscriber for the tray states.
bool HandleStartService(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Callback received when the team requests the competition start.
ros::ServiceServer submitTrayServiceServer
Service that allows a tray to be submitted for inspection.
std::string GoalID_t
Definition: ARIAC.hh:33
common::Time gameStartTime
The time specified in the object is relative to this time.
void OnTrayInfoReceived(const osrf_gear::KitTray::ConstPtr &trayMsg)
Callback for receiving tray state message.
void AssignGoal(const ariac::Goal &goal)
Assign a goal to be monitored by the scorer.
Class to store information about each object contained in a kit.
Definition: ARIAC.hh:241
The score of a competition run.
Definition: ARIAC.hh:128
transport::NodePtr node
Transportation node.
std::string currentState
Pointer to the current state.
ros::Publisher gazeboTaskStatePub
Publishes the Gazebo task state.
std::mutex mutex
A mutex to protect currentState.
AriacScorer ariacScorer
A scorer to mange the game score.
std::vector< ariac::Goal > goalsToAnnounce
Collection of goals to announce.
void ControlConveyorBelt(double velocity)
Set the velocity of the conveyor belt.
#define ROS_DEBUG_STREAM(args)
A scorer for the ARIAC game.
Definition: AriacScorer.h:36
GoalID_t goalID
The ID of this goal.
Definition: ARIAC.hh:322
std::string KitType_t
Definition: ARIAC.hh:31
std::stack< ariac::Goal > goalsInProgress
Collection of goals which have been announced but are not yet complete. The goal at the top of the st...
#define ROS_INFO_STREAM(args)
void StopCurrentGoal()
Stop scoring the current goal and assign the next goal on stack.
Class to store information about a kit.
Definition: ARIAC.hh:266
double timeSpentOnCurrentGoal
The time in seconds that has been spent on the current goal.
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
#define ROS_ERROR_STREAM(args)
ros::ServiceServer teamStartServiceServer
Service that allows the user to start the competition.
A plugin that orchestrates an ARIAC task. First of all, it loads a description of the goals...
#define ROS_ERROR(...)
#define ROSCONSOLE_DEFAULT_NAME
Definition: ARIAC.hh:27
KitType_t kitType
The type of the kit.
Definition: ARIAC.hh:284
Class to store information about a kit tray.
Definition: AriacKitTray.h:25


osrf_gear
Author(s):
autogenerated on Wed Sep 7 2016 03:48:12