problem.cpp
Go to the documentation of this file.
00001 #include "mrta/allocation.h"
00002 #include "mrta/architecture.h"
00003 #include "mrta/problem.h"
00004 #include "mrta/robot.h"
00005 #include "mrta/system.h"
00006 #include "mrta/task.h"
00007 
00008 namespace mrta
00009 {
00010 Problem::Problem(System* system, const QString& name,
00011                  ArchitectureConfig* architecture_config)
00012     : QObject(system), name_(name), architecture_(NULL)
00013 {
00014   setArchitecture(new Architecture(this, architecture_config));
00015 }
00016 
00017 Problem::~Problem()
00018 {
00019   setParent(NULL);
00020   ROS_INFO_STREAM("[~Problem] before");
00021   if (architecture_)
00022   {
00023     delete architecture_;
00024     architecture_ = NULL;
00025   }
00026   for (AllocationMap::iterator it(allocations_.begin());
00027        it != allocations_.end(); it++)
00028   {
00029     if (it.value())
00030     {
00031       delete it.value();
00032       allocations_[it.key()] = NULL;
00033     }
00034   }
00035   allocations_.clear();
00036   for (TaskMap::iterator it(tasks_.begin()); it != tasks_.end(); it++)
00037   {
00038     if (it.value())
00039     {
00040       delete it.value();
00041       tasks_[it.key()] = NULL;
00042     }
00043   }
00044   tasks_.clear();
00045   ROS_INFO_STREAM("[~Problem] after");
00046 }
00047 
00048 QString Problem::getName() const { return name_; }
00049 
00050 Architecture* Problem::getArchitecture() const { return architecture_; }
00051 
00052 Task* Problem::getTask(const QString& id) const
00053 {
00054   return tasks_.contains(id) ? tasks_[id] : NULL;
00055 }
00056 
00057 Allocation* Problem::getAllocation(const QString& id) const
00058 {
00059   return allocations_.contains(id) ? allocations_[id] : NULL;
00060 }
00061 
00062 QList<Task*> Problem::getTasks() const { return tasks_.values(); }
00063 
00064 QList<Allocation*> Problem::getAllocations() const
00065 {
00066   return allocations_.values();
00067 }
00068 
00069 void Problem::setArchitecture(Architecture* architecture)
00070 {
00071   if (architecture != architecture_)
00072   {
00073     if (architecture_)
00074     {
00075       delete architecture_;
00076     }
00077     architecture_ = architecture;
00078     emit changed();
00079   }
00080 }
00081 
00082 Allocation* Problem::addAllocation(Task* task, const QVector<Robot*>& robots)
00083 {
00084   Allocation* allocation = new Allocation(this, task, robots);
00085   allocations_[allocation->getId()] = allocation;
00086   connect(allocation, SIGNAL(stateChanged(int)), this,
00087           SLOT(allocationStateChanged(int)));
00088   emit allocationAdded(allocation->getId());
00089   return allocation;
00090 }
00091 
00092 bool Problem::isValid(Taxonomy::AllocationType type) const
00093 {
00094   return architecture_->isValid(type);
00095 }
00096 
00097 bool Problem::isValid(Taxonomy::RobotType type) const
00098 {
00099   return architecture_->isValid(type);
00100 }
00101 
00102 bool Problem::isValid(Taxonomy::TaskType type) const
00103 {
00104   return architecture_->isValid(type);
00105 }
00106 
00107 void Problem::taskStateChanged(int state)
00108 {
00109   Task* task = static_cast<Task*>(sender());
00110   if (task)
00111   {
00112     emit taskStateChanged(task->getId(), state);
00113     emit changed();
00114   }
00115 }
00116 
00117 void Problem::allocationStateChanged(int state)
00118 {
00119   Allocation* allocation = static_cast<Allocation*>(sender());
00120   if (allocation)
00121   {
00122     emit allocationStateChanged(allocation->getId(), state);
00123     emit changed();
00124   }
00125 }
00126 }


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