robots.cpp
Go to the documentation of this file.
00001 #include <QStringList>
00002 #include "rqt_mrta/config/application/robots.h"
00003 
00004 namespace rqt_mrta
00005 {
00006 namespace config
00007 {
00008 namespace application
00009 {
00010 Robots::Robots(QObject* parent) : AbstractConfig(parent) {}
00011 
00012 Robots::~Robots()
00013 {
00014   for (size_t index(0); index < robots_.count(); index++)
00015   {
00016     if (robots_[index])
00017     {
00018       delete robots_[index];
00019       robots_[index] = NULL;
00020     }
00021   }
00022   robots_.clear();
00023 }
00024 
00025 size_t Robots::count() const { return robots_.count(); }
00026 
00027 Robot* Robots::getRobot(size_t index) const
00028 {
00029   return index < robots_.count() ? robots_[index] : NULL;
00030 }
00031 
00032 Robot* Robots::addRobot()
00033 {
00034   Robot* robot = new Robot(this);
00035   robots_.append(robot);
00036   connect(robot, SIGNAL(changed()), this, SIGNAL(changed()));
00037   connect(robot, SIGNAL(idChanged(const QString&)), this,
00038           SLOT(robotIdChanged(const QString&)));
00039   connect(robot, SIGNAL(taskIdChanged(size_t, const QString&)), this,
00040           SLOT(taskIdChanged(size_t, const QString&)));
00041   connect(robot, SIGNAL(added(size_t)), this, SLOT(taskAdded(size_t)));
00042   connect(robot, SIGNAL(removed(const QString&)), this,
00043           SLOT(taskRemoved(const QString&)));
00044   connect(robot, SIGNAL(cleared()), this, SLOT(tasksCleared()));
00045   connect(robot, SIGNAL(destroyed()), this, SLOT(robotDestroyed()));
00046   emit added(robots_.count() - 1);
00047   emit changed();
00048   return robot;
00049 }
00050 
00051 void Robots::removeRobot(Robot* robot) { removeRobot(robots_.indexOf(robot)); }
00052 
00053 void Robots::removeRobot(size_t index)
00054 {
00055   if (index >= 0 && index < robots_.count())
00056   {
00057     QString robot_id(robots_[index]->getId());
00058     robots_.remove(index);
00059     emit removed(robot_id);
00060     emit changed();
00061   }
00062 }
00063 
00064 void Robots::clearRobots()
00065 {
00066   if (!robots_.isEmpty())
00067   {
00068     for (size_t index(0); index < robots_.count(); index++)
00069     {
00070       if (robots_[index])
00071       {
00072         delete robots_[index];
00073         robots_[index] = NULL;
00074       }
00075     }
00076     robots_.clear();
00077     emit cleared();
00078     emit changed();
00079   }
00080 }
00081 
00082 bool Robots::contains(const QString& id) const
00083 {
00084   for (size_t index(0); index < robots_.count(); index++)
00085   {
00086     if (robots_[index]->getId() == id)
00087     {
00088       return true;
00089     }
00090   }
00091   return false;
00092 }
00093 
00094 bool Robots::isEmpty() const { return robots_.isEmpty(); }
00095 
00096 void Robots::save(QSettings& settings) const
00097 {
00098   settings.beginGroup("robots");
00099   for (size_t index(0); index < robots_.count(); ++index)
00100   {
00101     settings.beginGroup("robot_" + QString::number(index));
00102     robots_[index]->save(settings);
00103     settings.endGroup();
00104   }
00105   settings.endGroup();
00106 }
00107 
00108 void Robots::load(QSettings& settings)
00109 {
00110   settings.beginGroup("robots");
00111   QStringList groups(settings.childGroups());
00112   size_t index(0);
00113   for (QStringList::iterator it(groups.begin()); it != groups.end(); it++)
00114   {
00115     Robot* robot =
00116         index < robots_.count() ? robot = robots_[index] : addRobot();
00117     settings.beginGroup(*it);
00118     robot->load(settings);
00119     settings.endGroup();
00120     ++index;
00121   }
00122   settings.endGroup();
00123   while (index < robots_.count())
00124   {
00125     removeRobot(index);
00126   }
00127 }
00128 
00129 void Robots::reset() { clearRobots(); }
00130 
00131 void Robots::write(QDataStream& stream) const
00132 {
00133   for (size_t index(0); index < robots_.count(); ++index)
00134   {
00135     robots_[index]->write(stream);
00136   }
00137 }
00138 
00139 void Robots::read(QDataStream& stream)
00140 {
00141   for (size_t index(0); index < robots_.count(); index++)
00142   {
00143     robots_[index]->read(stream);
00144   }
00145 }
00146 
00147 Robots& Robots::operator=(const Robots& config)
00148 {
00149   while (robots_.count() < config.robots_.count())
00150   {
00151     addRobot();
00152   }
00153   while (robots_.count() > config.robots_.count())
00154   {
00155     removeRobot(robots_.count() - 1);
00156   }
00157   for (size_t index(0); index < robots_.count(); ++index)
00158   {
00159     *robots_[index] = *config.robots_[index];
00160   }
00161   return *this;
00162 }
00163 
00164 QString Robots::validate() const
00165 {
00166   if (robots_.isEmpty())
00167   {
00168     return "Enter the system robots.";
00169   }
00170   QString validation;
00171   for (size_t i(0); i < robots_.count(); i++)
00172   {
00173     validation = robots_[i]->validate();
00174     if (!validation.isEmpty())
00175     {
00176       break;
00177     }
00178   }
00179   return validation;
00180 }
00181 
00182 void Robots::taskIdChanged(size_t task_index, const QString& task_id)
00183 {
00184   int index(robots_.indexOf(static_cast<Robot*>(sender())));
00185   if (index != -1)
00186   {
00187     emit taskIdChanged(index, task_index, task_id);
00188     emit changed();
00189   }
00190 }
00191 
00192 void Robots::taskAdded(size_t task_index)
00193 {
00194   int index(robots_.indexOf(static_cast<Robot*>(sender())));
00195   if (index != -1)
00196   {
00197     emit taskAdded(index, task_index);
00198     emit changed();
00199   }
00200 }
00201 
00202 void Robots::taskRemoved(const QString& task_id)
00203 {
00204   int index(robots_.indexOf(static_cast<Robot*>(sender())));
00205   if (index != -1)
00206   {
00207     emit taskRemoved(index, task_id);
00208     emit changed();
00209   }
00210 }
00211 
00212 void Robots::tasksCleared()
00213 {
00214   int index(robots_.indexOf(static_cast<Robot*>(sender())));
00215   if (index != -1)
00216   {
00217     emit tasksCleared(index);
00218     emit changed();
00219   }
00220 }
00221 
00222 void Robots::robotIdChanged(const QString& robot_id)
00223 {
00224   int index(robots_.indexOf(static_cast<Robot*>(sender())));
00225   if (index != -1)
00226   {
00227     emit robotIdChanged(index, robot_id);
00228     emit changed();
00229   }
00230 }
00231 
00232 void Robots::robotDestroyed()
00233 {
00234   Robot* robot = static_cast<Robot*>(sender());
00235   int index(robots_.indexOf(robot));
00236   if (index >= 0)
00237   {
00238     QString robot_id(robot->getId());
00239     robots_.remove(index);
00240     emit removed(robot_id);
00241     emit changed();
00242   }
00243 }
00244 }
00245 }
00246 }


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