layer.h
Go to the documentation of this file.
00001 #ifndef H_CANOPEN_LAYER
00002 #define H_CANOPEN_LAYER
00003 
00004 #include <vector>
00005 #include <boost/thread/shared_mutex.hpp>
00006 #include <boost/shared_ptr.hpp>
00007 #include <boost/atomic.hpp>
00008 #include <boost/exception/diagnostic_information.hpp>
00009 
00010 namespace canopen{
00011 
00012 class LayerStatus{
00013     mutable boost::mutex write_mutex_;
00014     enum State{
00015         OK = 0, WARN = 1, ERROR= 2, STALE = 3, UNBOUNDED = 3
00016     };
00017     boost::atomic<State> state;
00018     std::string reason_;
00019 
00020     virtual void set(const State &s, const std::string &r){
00021         boost::mutex::scoped_lock lock(write_mutex_);
00022         if(s > state) state = s;
00023         if(!r.empty()){
00024             if(reason_.empty())  reason_ = r;
00025             else reason_ += "; " + r;
00026         }
00027     }
00028 public:
00029     struct Ok { static const State state = OK; private: Ok();};
00030     struct Warn { static const State state = WARN; private: Warn(); };
00031     struct Error { static const State state = ERROR; private: Error(); };
00032     struct Stale { static const State state = STALE; private: Stale(); };
00033     struct Unbounded { static const State state = UNBOUNDED; private: Unbounded(); };
00034 
00035     template<typename T> bool bounded() const{ return state <= T::state; }
00036 
00037     LayerStatus() : state(OK) {}
00038 
00039     int get() const { return state; }
00040 
00041     const std::string reason() const { boost::mutex::scoped_lock lock(write_mutex_); return reason_; }
00042 
00043     const void warn(const std::string & r) { set(WARN, r); }
00044     const void error(const std::string & r) { set(ERROR, r); }
00045     const void stale(const std::string & r) { set(STALE, r); }
00046 };
00047 class LayerReport : public LayerStatus {
00048     std::vector<std::pair<std::string, std::string> > values_;
00049 public:
00050     const std::vector<std::pair<std::string, std::string> > &values() const { return values_; }
00051     template<typename T> void add(const std::string &key, const T &value) {
00052         std::stringstream str;
00053         str << value;
00054         values_.push_back(std::make_pair(key,str.str()));
00055     }
00056 };
00057 
00058 #define CATCH_LAYER_HANDLER_EXCEPTIONS(command, status)                           \
00059     try{ command; }                                                             \
00060     catch(std::exception &e) {status.error(boost::diagnostic_information(e)); }
00061 
00062 class Layer{
00063 public:
00064     enum LayerState{
00065         Off,
00066         Init,
00067         Shutdown,
00068         Error,
00069         Halt,
00070         Recover,
00071         Ready
00072     };
00073 
00074     const std::string name;
00075 
00076     void read(LayerStatus &status) {
00077         if(state > Off) CATCH_LAYER_HANDLER_EXCEPTIONS(handleRead(status, state), status);
00078     }
00079     void write(LayerStatus &status) {
00080         if(state > Off) CATCH_LAYER_HANDLER_EXCEPTIONS(handleWrite(status, state), status);
00081     }
00082     void diag(LayerReport &report) {
00083         if(state > Shutdown) CATCH_LAYER_HANDLER_EXCEPTIONS(handleDiag(report), report);
00084     }
00085     void init(LayerStatus &status) {
00086         if(state == Off){
00087             if(status.bounded<LayerStatus::Warn>()){
00088                 state = Init;
00089                 CATCH_LAYER_HANDLER_EXCEPTIONS(handleInit(status), status);
00090             }
00091             if(!status.bounded<LayerStatus::Warn>()) shutdown(status);
00092             else state = Ready;
00093         }
00094     }
00095     void shutdown(LayerStatus &status) {
00096         if(state != Off){
00097             state = Shutdown;
00098             CATCH_LAYER_HANDLER_EXCEPTIONS(handleShutdown(status), status);
00099             state = Off;
00100         }
00101     }
00102     void halt(LayerStatus &status) {
00103         if(state > Halt){
00104             state = Halt;
00105             CATCH_LAYER_HANDLER_EXCEPTIONS(handleHalt(status), status);
00106             state = Error;
00107         }
00108     }
00109     void recover(LayerStatus &status) {
00110         if(state == Error){
00111             if(status.bounded<LayerStatus::Warn>()){
00112                 state = Recover;
00113                 CATCH_LAYER_HANDLER_EXCEPTIONS(handleRecover(status), status);
00114             }
00115             if(!status.bounded<LayerStatus::Warn>()){
00116                 halt(status);
00117             }else{
00118                 state = Ready;
00119             }
00120         }
00121 
00122     }
00123 
00124     LayerState getLayerState() { return state; }
00125 
00126     Layer(const std::string &n) : name(n), state(Off) {}
00127 
00128     virtual ~Layer() {}
00129 
00130 protected:
00131     virtual void handleRead(LayerStatus &status, const LayerState &current_state)  = 0;
00132     virtual void handleWrite(LayerStatus &status, const LayerState &current_state)  = 0;
00133 
00134     virtual void handleDiag(LayerReport &report)  = 0;
00135 
00136     virtual void handleInit(LayerStatus &status)  = 0;
00137     virtual void handleShutdown(LayerStatus &status)  = 0;
00138 
00139     virtual void handleHalt(LayerStatus &status)  = 0;
00140     virtual void handleRecover(LayerStatus &status)  = 0;
00141 
00142 private:
00143     boost::atomic<LayerState> state;
00144 
00145 };
00146 
00147 template<typename T> class VectorHelper{
00148     typedef std::vector<boost::shared_ptr<T> > vector_type ;
00149     vector_type layers;
00150     boost::shared_mutex mutex;
00151 
00152     template<typename Bound, typename Iterator, typename Data, typename FuncType> Iterator call(FuncType func, Data &status, const Iterator &begin, const Iterator &end){
00153         bool okay_on_start = status.template bounded<Bound>();
00154 
00155         for(Iterator it = begin; it != end; ++it){
00156             ((**it).*func)(status);
00157             if(okay_on_start && !status.template bounded<Bound>()){
00158                 return it;
00159             }
00160         }
00161         return end;
00162     }
00163     template<typename Iterator, typename Data, typename FuncType> Iterator call(FuncType func, Data &status, const Iterator &begin, const Iterator &end){
00164         return call<LayerStatus::Unbounded, Iterator, Data>(func, status, begin, end);
00165     }
00166 protected:
00167     template<typename Bound, typename Data, typename FuncType> typename vector_type::iterator call(FuncType func, Data &status){
00168         boost::shared_lock<boost::shared_mutex> lock(mutex);
00169         return call<Bound>(func, status, layers.begin(), layers.end());
00170     }
00171     template<typename Data, typename FuncType> typename vector_type::iterator call(FuncType func, Data &status){
00172         boost::shared_lock<boost::shared_mutex> lock(mutex);
00173         return call<LayerStatus::Unbounded>(func, status, layers.begin(), layers.end());
00174     }
00175     template<typename Bound, typename Data, typename FuncType> typename vector_type::reverse_iterator call_rev(FuncType func, Data &status){
00176         boost::shared_lock<boost::shared_mutex> lock(mutex);
00177         return call<Bound>(func, status, layers.rbegin(), layers.rend());
00178     }
00179     template<typename Data, typename FuncType> typename vector_type::reverse_iterator call_rev(FuncType func, Data &status){
00180         boost::shared_lock<boost::shared_mutex> lock(mutex);
00181         return call<LayerStatus::Unbounded>(func, status, layers.rbegin(), layers.rend());
00182     }
00183     void destroy() { boost::unique_lock<boost::shared_mutex> lock(mutex); layers.clear(); }
00184 
00185 public:
00186     virtual void add(const boost::shared_ptr<T> &l) { boost::unique_lock<boost::shared_mutex> lock(mutex); layers.push_back(l); }
00187 
00188     template<typename Bound, typename Data, typename FuncType> bool callFunc(FuncType func, Data &status){
00189         boost::shared_lock<boost::shared_mutex> lock(mutex);
00190         return call<Bound>(func, status, layers.begin(), layers.end()) == layers.end();
00191     }
00192 };
00193 
00194 template<typename T=Layer> class LayerGroup : public Layer, public VectorHelper<T> {
00195 protected:
00196     template<typename Data, typename FuncType, typename FailType> void call_or_fail(FuncType func, FailType fail, Data &status){
00197         this->template call(func, status);
00198         if(!status.template bounded<LayerStatus::Warn>()){
00199             this->template call(fail, status);
00200             (this->*fail)(status);
00201         }
00202     }
00203     template<typename Data, typename FuncType, typename FailType> void call_or_fail_rev(FuncType func, FailType fail, Data &status){
00204         this->template call_rev(func, status);
00205         if(!status.template bounded<LayerStatus::Warn>()){
00206             this->template call_rev(fail, status);
00207             (this->*fail)(status);
00208         }
00209     }
00210 
00211     virtual void handleRead(LayerStatus &status, const LayerState &current_state) {
00212         this->template call_or_fail(&Layer::read, &Layer::halt, status);
00213     }
00214     virtual void handleWrite(LayerStatus &status, const LayerState &current_state) {
00215         this->template call_or_fail(&Layer::write, &Layer::halt, status);
00216     }
00217 
00218     virtual void handleDiag(LayerReport &report) { this->template call(&Layer::diag, report); }
00219 
00220     virtual void handleInit(LayerStatus &status) { this->template call<LayerStatus::Warn>(&Layer::init, status); }
00221     virtual void handleShutdown(LayerStatus &status) { this->template call(&Layer::shutdown, status); }
00222 
00223     virtual void handleHalt(LayerStatus &status) {  this->template call(&Layer::halt, status); }
00224     virtual void handleRecover(LayerStatus &status) { this->template call<LayerStatus::Warn>(&Layer::recover, status); }
00225 public:
00226     LayerGroup(const std::string &n) : Layer(n) {}
00227 };
00228 
00229 class LayerStack : public LayerGroup<>{
00230 
00231 protected:
00232     virtual void handleWrite(LayerStatus &status, const LayerState &current_state) { call_or_fail_rev(&Layer::write, &Layer::halt, status);}
00233     virtual void handleShutdown(LayerStatus &status) { call_rev(&Layer::shutdown, status); }
00234 public:
00235     LayerStack(const std::string &n) : LayerGroup(n) {}
00236 };
00237 
00238 template<typename T> class LayerGroupNoDiag : public LayerGroup<T>{
00239 public:
00240     LayerGroupNoDiag(const std::string &n) : LayerGroup<T>(n) {}
00241     virtual void handleDiag(LayerReport &report) {}
00242 };
00243 
00244 template<typename T> class DiagGroup : public VectorHelper<T>{
00245     typedef VectorHelper<T> V;
00246 public:
00247     virtual void diag(LayerReport &report){
00248         this->template call(&Layer::diag, report);
00249     }
00250 };
00251 
00252 
00253 
00254 } // namespace canopen
00255 
00256 #endif


canopen_master
Author(s): Mathias Lüdtke
autogenerated on Sun Sep 3 2017 03:10:42