master_plugin.cpp
Go to the documentation of this file.
00001 #include <class_loader/class_loader.h>
00002 #include <canopen_master/master.h>
00003 #include <socketcan_interface/reader.h>
00004 
00005 #include <set>
00006 
00007 namespace canopen {
00008 
00009 class ManagingSyncLayer: public SyncLayer {
00010 protected:
00011     boost::shared_ptr<can::CommInterface> interface_;
00012     boost::chrono::milliseconds step_, half_step_;
00013 
00014     std::set<void *> nodes_;
00015     boost::mutex nodes_mutex_;
00016     boost::atomic<size_t> nodes_size_;
00017     
00018     virtual void handleShutdown(LayerStatus &status) {
00019     }
00020 
00021     virtual void handleHalt(LayerStatus &status)  { /* nothing to do */ }
00022     virtual void handleDiag(LayerReport &report)  { /* TODO */ }
00023     virtual void handleRecover(LayerStatus &status)  { /* TODO */ }
00024 
00025 public:
00026     ManagingSyncLayer(const SyncProperties &p, boost::shared_ptr<can::CommInterface> interface)
00027     : SyncLayer(p), interface_(interface), step_(p.period_ms_), half_step_(p.period_ms_/2), nodes_size_(0)
00028     {
00029     }
00030 
00031     virtual void addNode(void * const ptr) {
00032         boost::mutex::scoped_lock lock(nodes_mutex_);
00033         nodes_.insert(ptr);
00034         nodes_size_ = nodes_.size();
00035     }
00036     virtual void removeNode(void * const ptr)  {
00037         boost::mutex::scoped_lock lock(nodes_mutex_);
00038         nodes_.erase(ptr);
00039         nodes_size_ = nodes_.size();
00040     }
00041 };
00042 
00043     
00044 class SimpleSyncLayer: public ManagingSyncLayer {
00045     time_point read_time_, write_time_;
00046 protected:
00047     virtual void handleRead(LayerStatus &status, const LayerState &current_state) {
00048         if(current_state > Init){
00049             boost::this_thread::sleep_until(read_time_);
00050             write_time_ += step_;
00051         }
00052     }
00053     virtual void handleWrite(LayerStatus &status, const LayerState &current_state) {
00054         if(current_state > Init){
00055             can::Frame frame(properties.header_, 0);
00056             boost::this_thread::sleep_until(write_time_);
00057             if(nodes_size_){ //)
00058                 interface_->send(frame);
00059             }
00060             read_time_ = get_abs_time(half_step_);
00061         }
00062     }
00063 
00064     virtual void handleInit(LayerStatus &status){
00065         write_time_ = get_abs_time(step_);
00066         read_time_ = get_abs_time(half_step_);
00067     }
00068 public:
00069     SimpleSyncLayer(const SyncProperties &p, boost::shared_ptr<can::CommInterface> interface)
00070     : ManagingSyncLayer(p, interface) {}
00071 };
00072 
00073 class ExternalSyncLayer: public ManagingSyncLayer {
00074     can::BufferedReader reader_;
00075 protected:
00076     virtual void handleRead(LayerStatus &status, const LayerState &current_state) {
00077         can::Frame msg;
00078         if(current_state > Init){
00079             if(reader_.readUntil(&msg, get_abs_time(step_))){ // wait for sync
00080                 boost::this_thread::sleep_until(get_abs_time(half_step_)); // shift readout to middle of period
00081             }
00082         }
00083     }
00084     virtual void handleWrite(LayerStatus &status, const LayerState &current_state) {
00085         // nothing to do here
00086     }
00087     virtual void handleInit(LayerStatus &status){
00088         reader_.listen(interface_, can::MsgHeader(properties.header_));
00089     }
00090 public:
00091     ExternalSyncLayer(const SyncProperties &p, boost::shared_ptr<can::CommInterface> interface)
00092     : ManagingSyncLayer(p, interface), reader_(true,1) {}
00093 };
00094 
00095 
00096 template<typename SyncType> class WrapMaster: public Master{
00097     boost::shared_ptr<can::CommInterface> interface_;
00098 public:
00099     virtual boost::shared_ptr<SyncLayer> getSync(const SyncProperties &properties){
00100         return boost::make_shared<SyncType>(properties, interface_);
00101     }
00102     WrapMaster(boost::shared_ptr<can::CommInterface> interface) : interface_(interface)  {}
00103 
00104     class Allocator : public Master::Allocator{
00105     public:
00106         virtual boost::shared_ptr<Master> allocate(const std::string &name,  boost::shared_ptr<can::CommInterface> interface){
00107             return boost::make_shared<WrapMaster>(interface);
00108         }
00109     };
00110 };
00111 
00112 typedef WrapMaster<SimpleSyncLayer> SimpleMaster;
00113 typedef WrapMaster<ExternalSyncLayer> ExternalMaster;
00114 }
00115 boost::shared_ptr<canopen::Master> canopen::LocalMaster::Allocator::allocate(const std::string &name, boost::shared_ptr<can::CommInterface> interface) {
00116     return boost::make_shared<canopen::LocalMaster>(interface);
00117 }
00118 boost::shared_ptr<canopen::Master> canopen::SharedMaster::Allocator::allocate(const std::string &name, boost::shared_ptr<can::CommInterface> interface) {
00119     return boost::make_shared<canopen::SharedMaster>(name, interface);
00120 }
00121 
00122 boost::shared_ptr<canopen::Master> canopen::UnrestrictedMaster::Allocator::allocate(const std::string &name, boost::shared_ptr<can::CommInterface> interface) {
00123     return boost::make_shared<canopen::UnrestrictedMaster>(name, interface);
00124 }
00125 
00126 CLASS_LOADER_REGISTER_CLASS(canopen::LocalMaster::Allocator, canopen::Master::Allocator);
00127 CLASS_LOADER_REGISTER_CLASS(canopen::SharedMaster::Allocator, canopen::Master::Allocator);
00128 CLASS_LOADER_REGISTER_CLASS(canopen::UnrestrictedMaster::Allocator, canopen::Master::Allocator);
00129 CLASS_LOADER_REGISTER_CLASS(canopen::SimpleMaster::Allocator, canopen::Master::Allocator);
00130 CLASS_LOADER_REGISTER_CLASS(canopen::ExternalMaster::Allocator, canopen::Master::Allocator);
00131 


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