allocation.cpp
Go to the documentation of this file.
00001 #include "mrta/allocation.h"
00002 #include "mrta/problem.h"
00003 #include "mrta/robot.h"
00004 #include "mrta/task.h"
00005 #include <ros/time.h>
00006 
00007 namespace mrta
00008 {
00009 Allocation::Allocation(Problem* problem, Task* task,
00010                        const QVector<Robot*>& robots)
00011     : QObject(problem), task_(task), state_(OnHold),
00012       id_(task->getId() + "-" + QString::number(ros::Time::now().toSec()))
00013 
00014 {
00015   setRobots(robots);
00016   connect(task_, SIGNAL(stateChanged(int)), this, SLOT(taskStateChanged(int)));
00017 }
00018 
00019 Allocation::~Allocation()
00020 {
00021   ROS_INFO_STREAM("[~Allocation] before");
00022   task_ = NULL;
00023   robots_.clear();
00024   ROS_INFO_STREAM("[~Allocation] after");
00025 }
00026 
00027 QString Allocation::getId() const { return id_; }
00028 
00029 Task* Allocation::getTask() const { return task_; }
00030 
00031 QVector<Robot*> Allocation::getRobots() const { return robots_; }
00032 
00033 void Allocation::setRobots(const QVector<Robot*>& robots)
00034 {
00035   if (robots != robots_)
00036   {
00037     if (!robots_.isEmpty())
00038     {
00039       for (size_t index(0); index < robots_.count(); index++)
00040       {
00041         disconnect(robots_[index], SIGNAL(stateChanged(int)), this,
00042                    SLOT(robotStateChanged(int)));
00043       }
00044     }
00045     robots_ = robots;
00046     if (!robots_.isEmpty())
00047     {
00048       for (size_t index(0); index < robots_.count(); index++)
00049       {
00050         connect(robots_[index], SIGNAL(stateChanged(int)), this,
00051                 SLOT(robotStateChanged(int)));
00052       }
00053     }
00054     emit changed();
00055   }
00056 }
00057 
00058 void Allocation::setState(Allocation::State state)
00059 {
00060   if (state != state_)
00061   {
00062     state_ = state;
00063     emit stateChanged(state);
00064     emit changed();
00065   }
00066 }
00067 
00068 void Allocation::robotStateChanged(int state)
00069 {
00070   Robot* robot = static_cast<Robot*>(sender());
00071 }
00072 
00073 void Allocation::taskStateChanged(int state)
00074 {
00075   Task* task = static_cast<Task*>(sender());
00076 }
00077 }


rqt_mrta
Author(s): Adriano Henrique Rossette Leite
autogenerated on Thu Jun 6 2019 18:50:52