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>    34 #include <std_msgs/Float32.h>    35 #include <std_msgs/String.h>    36 #include <std_srvs/Trigger.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"    56     public: physics::WorldPtr 
world;
    59     public: sdf::ElementPtr 
sdf;
    75     public: std::unique_ptr<ros::NodeHandle> 
rosnode;
    99     public: transport::NodePtr 
node;
   135   _msgGoal.goal_id.data = _goal.goalID;
   136   for (
const auto item : _goal.kits)
   138     osrf_gear::Kit msgKit;
   139     msgKit.kit_type.data = item.first;
   140     for (
const auto &obj : item.second.objects)
   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;
   153       msgKit.objects.push_back(msgObj);
   155     _msgGoal.kits.push_back(msgKit);
   168   this->
dataPtr->rosnode->shutdown();
   173   sdf::ElementPtr _sdf)
   175   GZ_ASSERT(_world, 
"ROSAriacTaskManagerPlugin world pointer is NULL");
   176   GZ_ASSERT(_sdf, 
"ROSAriacTaskManagerPlugin sdf pointer is NULL");
   180   std::string robotNamespace = 
"";
   181   if (_sdf->HasElement(
"robot_namespace"))
   183     robotNamespace = _sdf->GetElement(
   184       "robot_namespace")->Get<std::string>() + 
"/";
   187   std::string teamStartServiceName = 
"start";
   188   if (_sdf->HasElement(
"team_start_service_name"))
   189     teamStartServiceName = _sdf->Get<std::string>(
"team_start_service_name");
   191   std::string gazeboTaskStateTopic = 
"competition_state";
   192   if (_sdf->HasElement(
"gazebo_task_state_topic"))
   193     gazeboTaskStateTopic = _sdf->Get<std::string>(
"gazebo_task_state_topic");
   195   std::string gazeboTaskScoreTopic = 
"current_score";
   196   if (_sdf->HasElement(
"gazebo_task_score_topic"))
   197     gazeboTaskScoreTopic = _sdf->Get<std::string>(
"gazebo_task_score_topic");
   199   std::string conveyorControlTopic = 
"conveyor/control";
   200   if (_sdf->HasElement(
"conveyor_control_topic"))
   201     conveyorControlTopic = _sdf->Get<std::string>(
"conveyor_control_topic");
   203   std::string populationActivateTopic = 
"populate_belt";
   204   if (_sdf->HasElement(
"population_activate_topic"))
   205     populationActivateTopic = _sdf->Get<std::string>(
"population_activate_topic");
   207   std::string goalsTopic = 
"orders";
   208   if (_sdf->HasElement(
"goals_topic"))
   209     goalsTopic = _sdf->Get<std::string>(
"goals_topic");
   211   std::string submitTrayServiceName = 
"submit_tray";
   212   if (_sdf->HasElement(
"submit_tray_service_name"))
   213     submitTrayServiceName = _sdf->Get<std::string>(
"submit_tray_service_name");
   217   sdf::ElementPtr goalElem = NULL;
   218   if (_sdf->HasElement(
"goal"))
   220     goalElem = _sdf->GetElement(
"goal");
   223   unsigned int goalCount = 0;
   227     if (!goalElem->HasElement(
"start_time"))
   229       gzerr << 
"Unable to find <start_time> element in <goal>. Ignoring" << std::endl;
   230       goalElem = goalElem->GetNextElement(
"goal");
   233     sdf::ElementPtr startTimeElement = goalElem->GetElement(
"start_time");
   234     double startTime = startTimeElement->Get<
double>();
   237     double allowedTime = std::numeric_limits<double>::infinity();
   238     if (goalElem->HasElement(
"allowed_time"))
   240       sdf::ElementPtr allowedTimeElement = goalElem->GetElement(
"allowed_time");
   241       allowedTime = allowedTimeElement->Get<
double>();
   245     if (!goalElem->HasElement(
"kit"))
   247       gzerr << 
"Unable to find <kit> element in <goal>. Ignoring" << std::endl;
   248       goalElem = goalElem->GetNextElement(
"goal");
   253     std::map<std::string, ariac::Kit> kits;
   255     sdf::ElementPtr kitElem = goalElem->GetElement(
"kit");
   259       if (!kitElem->HasElement(
"object"))
   261         gzerr << 
"Unable to find <object> element in <kit>. Ignoring"   263         kitElem = kitElem->GetNextElement(
"kit");
   271       if (kitElem->HasElement(
"kit_type"))
   273         kitType = kitElem->Get<std::string>(
"kit_type");
   278       sdf::ElementPtr objectElem = kitElem->GetElement(
"object");
   282         if (!objectElem->HasElement(
"type"))
   284           gzerr << 
"Unable to find <type> in object.\n";
   285           objectElem = objectElem->GetNextElement(
"object");
   288         sdf::ElementPtr typeElement = objectElem->GetElement(
"type");
   289         std::string type = typeElement->Get<std::string>();
   292         if (!objectElem->HasElement(
"pose"))
   294           gzerr << 
"Unable to find <pose> in object.\n";
   295           objectElem = objectElem->GetNextElement(
"object");
   298         sdf::ElementPtr poseElement = objectElem->GetElement(
"pose");
   299         math::Pose pose = poseElement->Get<math::Pose>();
   305         objectElem = objectElem->GetNextElement(
"object");
   311       kitElem = kitElem->GetNextElement(
"kit");
   316     ariac::Goal goal = {goalID, startTime, allowedTime, kits, 0.0};
   317     this->
dataPtr->goalsToAnnounce.push_back(goal);
   319     goalElem = goalElem->GetNextElement(
"goal");
   323   std::sort(this->
dataPtr->goalsToAnnounce.begin(), this->
dataPtr->goalsToAnnounce.end());
   340     osrf_gear::Goal>(goalsTopic, 1000, 
true);  
   343   this->
dataPtr->gazeboTaskStatePub = this->
dataPtr->rosnode->advertise<
   344     std_msgs::String>(gazeboTaskStateTopic, 1000);
   347   this->
dataPtr->gazeboTaskScorePub = this->
dataPtr->rosnode->advertise<
   348     std_msgs::Float32>(gazeboTaskScoreTopic, 1000);
   351   this->
dataPtr->teamStartServiceServer =
   352     this->
dataPtr->rosnode->advertiseService(teamStartServiceName,
   356   this->
dataPtr->submitTrayServiceServer =
   357     this->
dataPtr->rosnode->advertiseService(submitTrayServiceName,
   361   this->
dataPtr->conveyorControlClient =
   362     this->
dataPtr->rosnode->serviceClient<osrf_gear::ConveyorBeltControl>(
   363       conveyorControlTopic);
   366   this->
dataPtr->node = transport::NodePtr(
new transport::Node());
   369     this->
dataPtr->node->Advertise<msgs::GzString>(populationActivateTopic);
   374   this->
dataPtr->gripperStateSub = this->
dataPtr->rosnode->subscribe(
   378   this->
dataPtr->gameStartTime = this->
dataPtr->world->GetSimTime();
   380   this->
dataPtr->connection = event::Events::ConnectWorldUpdateEnd(
   387   std::lock_guard<std::mutex> lock(this->
dataPtr->mutex);
   388   auto currentSimTime = this->
dataPtr->world->GetSimTime();
   390   double elapsedTime = (currentSimTime - this->
dataPtr->lastUpdateTime).Double();
   391   if (this->
dataPtr->currentState == 
"ready")
   393     this->
dataPtr->gameStartTime = currentSimTime;
   394     this->
dataPtr->currentState = 
"go";
   399   else if (this->
dataPtr->currentState == 
"go")
   405     this->
dataPtr->ariacScorer.Update(elapsedTime);
   406     auto gameScore = this->
dataPtr->ariacScorer.GetGameScore();
   407     if (gameScore.total() != this->
dataPtr->currentGameScore.total())
   410       this->
dataPtr->currentGameScore = gameScore;
   413     if (!this->
dataPtr->goalsInProgress.empty())
   415       this->
dataPtr->goalsInProgress.top().timeTaken += elapsedTime;
   416       auto goalID = this->
dataPtr->goalsInProgress.top().goalID;
   418       this->
dataPtr->timeSpentOnCurrentGoal = this->
dataPtr->goalsInProgress.top().timeTaken;
   421       bool goalCompleted = this->
dataPtr->ariacScorer.IsCurrentGoalComplete();
   430         if (this->
dataPtr->timeSpentOnCurrentGoal > this->dataPtr->goalsInProgress.top().allowedTime)
   438     if (this->
dataPtr->goalsInProgress.empty() && this->
dataPtr->goalsToAnnounce.empty())
   440       this->
dataPtr->currentGameScore.totalProcessTime =
   441         (currentSimTime - this->
dataPtr->gameStartTime).Double();
   442       this->
dataPtr->currentState = 
"end_game";
   445   else if (this->
dataPtr->currentState == 
"end_game")
   449     this->
dataPtr->currentState = 
"done";
   453   std_msgs::Float32 scoreMsg;
   454   scoreMsg.data = this->
dataPtr->currentGameScore.total();
   455   this->
dataPtr->gazeboTaskScorePub.publish(scoreMsg);
   457   std_msgs::String stateMsg;
   458   stateMsg.data = this->
dataPtr->currentState;
   459   this->
dataPtr->gazeboTaskStatePub.publish(stateMsg);
   461   this->
dataPtr->lastUpdateTime = currentSimTime;
   467   if (this->
dataPtr->goalsToAnnounce.empty())
   471   auto elapsed = this->
dataPtr->world->GetSimTime() - this->
dataPtr->gameStartTime;
   472   if (elapsed.Double() >= this->
dataPtr->goalsToAnnounce.front().startTime)
   474     auto goal = this->
dataPtr->goalsToAnnounce.front();
   478     this->
dataPtr->goalsToAnnounce.erase(this->
dataPtr->goalsToAnnounce.begin());
   486   std_srvs::Trigger::Request & req,
   487   std_srvs::Trigger::Response & res)
   490   std::lock_guard<std::mutex> lock(this->
dataPtr->mutex);
   492   if (this->
dataPtr->currentState == 
"init") {
   493     this->
dataPtr->currentState = 
"ready";
   495     res.message = 
"competition started successfully!";
   499   res.message = 
"cannot start if not in 'init' state";
   505   osrf_gear::SubmitTray::Request & req,
   506   osrf_gear::SubmitTray::Response & res)
   508   std::lock_guard<std::mutex> lock(this->
dataPtr->mutex);
   510   if (this->
dataPtr->currentState != 
"go") {
   511     ROS_ERROR(
"Competition is not running so trays cannot be submitted.");
   516   if (!this->
dataPtr->ariacScorer.GetTrayById(req.tray_id.data, kitTray))
   523   res.inspection_result = this->
dataPtr->ariacScorer.SubmitTray(kitTray).total();
   531   if (!this->
dataPtr->conveyorControlClient.exists())
   533     this->
dataPtr->conveyorControlClient.waitForExistence();
   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) {
   551   gazebo::msgs::GzString 
msg;
   552   msg.set_data(
"restart");
   553   this->
dataPtr->populatePub->Publish(msg);
   561     osrf_gear::Goal goalMsg;
   563     this->
dataPtr->goalPub.publish(goalMsg);
   566     gzdbg << 
"Assigning order: " << goal << std::endl;
   567     this->
dataPtr->ariacScorer.AssignGoal(goal);
   573   if (this->
dataPtr->goalsInProgress.size())
   576     this->
dataPtr->goalsInProgress.pop();
   577     this->
dataPtr->ariacScorer.UnassignCurrentGoal(this->
dataPtr->timeSpentOnCurrentGoal);
   580   if (this->
dataPtr->goalsInProgress.size())
   583     auto goal = this->
dataPtr->goalsInProgress.top();
 void PopulateConveyorBelt()
Start populating the conveyor belt. 
ros::ServiceClient conveyorControlClient
Client for controlling the conveyor. 
std::vector< KitObject > objects
A kit is composed of multiple objects. 
transport::PublisherPtr populatePub
Publisher for enabling the object population on the conveyor. 
static void fillGoalMsg(const ariac::Goal &_goal, osrf_gear::Goal &_msgGoal)
void OnUpdate()
Update the plugin. 
void ProcessGoalsToAnnounce()
Decide whether to announce a new goal. 
Class to store information about a goal. 
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. 
ROSAriacTaskManagerPlugin()
Constructor. 
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. 
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. 
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. 
sdf::ElementPtr sdf
SDF pointer. 
The score of a competition run. 
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. 
ros::Publisher goalPub
Publishes a goal. 
#define ROS_DEBUG_STREAM(args)
A scorer for the ARIAC game. 
GoalID_t goalID
The ID of this goal. 
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. 
virtual ~ROSAriacTaskManagerPlugin()
Destructor. 
Class to store information about a kit. 
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. 
physics::WorldPtr world
World pointer. 
A plugin that orchestrates an ARIAC task. First of all, it loads a description of the goals...
#define ROSCONSOLE_DEFAULT_NAME
KitType_t kitType
The type of the kit. 
Class to store information about a kit tray.