Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef MODE_H
00019 #define MODE_H
00020
00021 #include <ros/ros.h>
00022 #include <colorUtils.h>
00023 #include <boost/signals2.hpp>
00024 #include <boost/thread.hpp>
00025
00026 class Mode
00027 {
00028 public:
00029 Mode(int priority = 0, double freq = 0, int pulses = 0, double timeout = 0)
00030 : _priority(priority), _freq(freq), _pulses(pulses), _timeout(timeout),
00031 _finished(false), _pulsed(0), _isStopRequested(false), _isPauseRequested(false),
00032 _isRunning(false)
00033 {
00034 if(this->getFrequency() == 0.0)
00035 this->setFrequency(1.0);
00036 }
00037 virtual ~Mode(){}
00038
00039 void start()
00040 {
00041 if(_thread == NULL)
00042 _thread.reset(new boost::thread(&Mode::run, this));
00043 if(isPauseRequested())
00044 {
00045 boost::mutex::scoped_lock lock(_mutex_pause);
00046 _isPauseRequested = false;
00047 _cond_pause.notify_one();
00048 }
00049 _isRunning = true;
00050 }
00051
00052 void stop()
00053 {
00054 _mutex.lock();
00055 _isStopRequested = true;
00056 _mutex.unlock();
00057 if(isPauseRequested())
00058 {
00059 _isPauseRequested = false;
00060 boost::mutex::scoped_lock lock(_mutex_pause);
00061 _cond_pause.notify_one();
00062 }
00063 if(_thread != NULL)
00064 {
00065 _thread->join();
00066 _thread.reset();
00067 }
00068 _isStopRequested = false;
00069 _isRunning = false;
00070 }
00071
00072 void pause()
00073 {
00074 _mutex.lock();
00075 _isPauseRequested = true;
00076 _mutex.unlock();
00077 _isRunning = false;
00078 }
00079
00080 virtual void execute() = 0;
00081
00082 virtual std::string getName() = 0;
00083
00084 bool finished(){ return _finished; }
00085
00086 void setPriority(int priority){ _priority = priority; }
00087 int getPriority(){ return _priority; }
00088
00089 void setTimeout(double timeout){ _timeout = timeout; }
00090 double getTimeout(){ return _timeout; }
00091
00092 void setFrequency(double freq){ _freq = freq; }
00093 double getFrequency(){ return _freq; }
00094
00095 void setPulses(int pulses){ _pulses = pulses; }
00096 int getPulses(){ return _pulses; }
00097
00098 int pulsed(){ return _pulsed; }
00099
00100 void setColor(color::rgba color){ _color = color; }
00101 color::rgba getColor(){ return _color; }
00102
00103 void setActualColor(color::rgba color){ _actualColor = color; }
00104 color::rgba getActualColor(){ return _color; }
00105
00106 bool isRunning(){ return _isRunning; }
00107
00108 boost::signals2::signal<void (color::rgba color)>* signalColorReady(){ return &m_sigColorReady; }
00109 boost::signals2::signal<void (std::vector<color::rgba> colors)>* signalColorsReady(){ return &m_sigColorsReady; }
00110 boost::signals2::signal<void (int)>* signalModeFinished(){ return &m_sigFinished; }
00111
00112 protected:
00113 int _priority;
00114 double _freq;
00115 int _pulses;
00116 double _timeout;
00117
00118 bool _finished;
00119 int _pulsed;
00120
00121 color::rgba _color;
00122 std::vector<color::rgba> _colors;
00123 color::rgba _actualColor;
00124 color::rgba _init_color;
00125
00126 static const unsigned int UPDATE_RATE_HZ = 100;
00127
00128 boost::signals2::signal<void (color::rgba color)> m_sigColorReady;
00129 boost::signals2::signal<void (std::vector<color::rgba> colors)> m_sigColorsReady;
00130 boost::signals2::signal<void (int)> m_sigFinished;
00131
00132 private:
00133 boost::shared_ptr<boost::thread> _thread;
00134 boost::mutex _mutex;
00135 boost::mutex _mutex_pause;
00136 bool _isStopRequested;
00137 bool _isPauseRequested;
00138 bool _isRunning;
00139
00140 boost::condition_variable _cond_pause;
00141
00142 bool isStopRequested()
00143 {
00144 bool ret;
00145 _mutex.lock();
00146 ret = _isStopRequested;
00147 _mutex.unlock();
00148 return ret;
00149 }
00150
00151 bool isPauseRequested()
00152 {
00153 bool ret;
00154 _mutex.lock();
00155 ret = _isPauseRequested;
00156 _mutex.unlock();
00157 return ret;
00158 }
00159
00160 protected:
00161 virtual void run()
00162 {
00163 ros::Rate r(UPDATE_RATE_HZ);
00164
00165 ros::Time timeStart = ros::Time::now();
00166
00167 while(!isStopRequested() && !ros::isShuttingDown())
00168 {
00169 while(isPauseRequested())
00170 {
00171 boost::mutex::scoped_lock lock(_mutex_pause);
00172 _cond_pause.wait(lock);
00173 }
00174 this->execute();
00175
00176 if((this->getPulses() != 0) &&
00177 (this->getPulses() <= this->pulsed()))
00178 break;
00179
00180 if(this->getTimeout() != 0)
00181 {
00182 ros::Duration timePassed = ros::Time::now() - timeStart;
00183 if(timePassed.toSec() >= this->getTimeout())
00184 break;
00185 }
00186 r.sleep();
00187 }
00188 ROS_DEBUG("Mode %s finished",this->getName().c_str());
00189 if(!isStopRequested())
00190 m_sigFinished(this->getPriority());
00191 }
00192 };
00193
00194 #endif