master_plugin.cpp
Go to the documentation of this file.
4 
5 #include <set>
6 
7 namespace canopen {
8 
9 class ManagingSyncLayer: public SyncLayer {
10 protected:
12  boost::chrono::milliseconds step_, half_step_;
13 
14  std::set<void *> nodes_;
15  boost::mutex nodes_mutex_;
16  std::atomic<size_t> nodes_size_;
17 
18  virtual void handleShutdown(LayerStatus &status) {
19  }
20 
21  virtual void handleHalt(LayerStatus &status) { /* nothing to do */ }
22  virtual void handleDiag(LayerReport &report) { /* TODO */ }
23  virtual void handleRecover(LayerStatus &status) { /* TODO */ }
24 
25 public:
27  : SyncLayer(p), interface_(interface), step_(p.period_ms_), half_step_(p.period_ms_/2), nodes_size_(0)
28  {
29  }
30 
31  virtual void addNode(void * const ptr) {
32  boost::mutex::scoped_lock lock(nodes_mutex_);
33  nodes_.insert(ptr);
34  nodes_size_ = nodes_.size();
35  }
36  virtual void removeNode(void * const ptr) {
37  boost::mutex::scoped_lock lock(nodes_mutex_);
38  nodes_.erase(ptr);
39  nodes_size_ = nodes_.size();
40  }
41 };
42 
43 
47  uint8_t overflow_;
48 
49  void resetCounter(){
50  frame_.data[0] = 1; // SYNC counter starts at 1
51  }
53  if (frame_.dlc > 0) { // sync counter is used
54  if (frame_.data[0] >= overflow_) {
55  resetCounter();
56  }else{
57  ++frame_.data[0];
58  }
59  }
60  }
61 protected:
62  virtual void handleRead(LayerStatus &status, const LayerState &current_state) {
63  if(current_state > Init){
64  boost::this_thread::sleep_until(read_time_);
65  write_time_ += step_;
66  }
67  }
68  virtual void handleWrite(LayerStatus &status, const LayerState &current_state) {
69  if(current_state > Init){
70  boost::this_thread::sleep_until(write_time_);
72  if(nodes_size_){ //)
73  interface_->send(frame_);
74  }
76  }
77  }
78 
79  virtual void handleInit(LayerStatus &status){
82  }
83 public:
85  : ManagingSyncLayer(p, interface), frame_(p.header_, 0), overflow_(p.overflow_) {
86  if(overflow_ == 1 || overflow_ > 240){
87  BOOST_THROW_EXCEPTION(Exception("SYNC counter overflow is invalid"));
88  }else if(overflow_ > 1){
89  frame_.dlc = 1;
90  resetCounter();
91  }
92  }
93 };
94 
97 protected:
98  virtual void handleRead(LayerStatus &status, const LayerState &current_state) {
99  can::Frame msg;
100  if(current_state > Init){
101  if(reader_.readUntil(&msg, get_abs_time(step_))){ // wait for sync
102  boost::this_thread::sleep_until(get_abs_time(half_step_)); // shift readout to middle of period
103  }
104  }
105  }
106  virtual void handleWrite(LayerStatus &status, const LayerState &current_state) {
107  // nothing to do here
108  }
109  virtual void handleInit(LayerStatus &status){
111  }
112 public:
114  : ManagingSyncLayer(p, interface), reader_(true,1) {}
115 };
116 
117 
118 template<typename SyncType> class WrapMaster: public Master{
120 public:
121  virtual SyncLayerSharedPtr getSync(const SyncProperties &properties){
122  return std::make_shared<SyncType>(properties, interface_);
123  }
125 
126  class Allocator : public Master::Allocator{
127  public:
128  virtual MasterSharedPtr allocate(const std::string &name, can::CommInterfaceSharedPtr interface){
129  return std::make_shared<WrapMaster>(interface);
130  }
131  };
132 };
133 
136 }
canopen::SimpleSyncLayer::resetCounter
void resetCounter()
Definition: master_plugin.cpp:49
canopen::SimpleSyncLayer::frame_
can::Frame frame_
Definition: master_plugin.cpp:46
canopen.h
can::Frame
can::BufferedReader::listen
void listen(CommInterfaceSharedPtr interface)
canopen::SimpleSyncLayer::handleInit
virtual void handleInit(LayerStatus &status)
Definition: master_plugin.cpp:79
canopen::WrapMaster::getSync
virtual SyncLayerSharedPtr getSync(const SyncProperties &properties)
Definition: master_plugin.cpp:121
canopen::SimpleSyncLayer
Definition: master_plugin.cpp:44
canopen::ManagingSyncLayer::addNode
virtual void addNode(void *const ptr)
Definition: master_plugin.cpp:31
canopen::ExternalSyncLayer::handleRead
virtual void handleRead(LayerStatus &status, const LayerState &current_state)
Definition: master_plugin.cpp:98
canopen::SimpleSyncLayer::overflow_
uint8_t overflow_
Definition: master_plugin.cpp:47
canopen::ManagingSyncLayer::ManagingSyncLayer
ManagingSyncLayer(const SyncProperties &p, can::CommInterfaceSharedPtr interface)
Definition: master_plugin.cpp:26
reader.h
canopen::SyncProperties
Definition: canopen.h:170
can::Frame::dlc
unsigned char dlc
canopen::Layer::Init
@ Init
Definition: layer.h:67
canopen::ManagingSyncLayer::half_step_
boost::chrono::milliseconds half_step_
Definition: master_plugin.cpp:12
canopen::ManagingSyncLayer::handleRecover
virtual void handleRecover(LayerStatus &status)
Definition: master_plugin.cpp:23
canopen::Layer::LayerState
LayerState
Definition: layer.h:65
CLASS_LOADER_REGISTER_CLASS
CLASS_LOADER_REGISTER_CLASS(canopen::SimpleMaster::Allocator, canopen::Master::Allocator)
canopen::WrapMaster
Definition: master_plugin.cpp:118
canopen::ManagingSyncLayer
Definition: master_plugin.cpp:9
canopen::ExternalSyncLayer::ExternalSyncLayer
ExternalSyncLayer(const SyncProperties &p, can::CommInterfaceSharedPtr interface)
Definition: master_plugin.cpp:113
can::CommInterfaceSharedPtr
std::shared_ptr< CommInterface > CommInterfaceSharedPtr
canopen::ManagingSyncLayer::handleDiag
virtual void handleDiag(LayerReport &report)
Definition: master_plugin.cpp:22
canopen::ManagingSyncLayer::handleHalt
virtual void handleHalt(LayerStatus &status)
Definition: master_plugin.cpp:21
canopen::time_point
boost::chrono::high_resolution_clock::time_point time_point
Definition: canopen.h:18
canopen::ManagingSyncLayer::removeNode
virtual void removeNode(void *const ptr)
Definition: master_plugin.cpp:36
can::BufferedReader::readUntil
bool readUntil(can::Frame *msg, boost::chrono::high_resolution_clock::time_point abs_time)
canopen::Master::MasterSharedPtr
std::shared_ptr< Master > MasterSharedPtr
Definition: canopen.h:319
canopen::WrapMaster::WrapMaster
WrapMaster(can::CommInterfaceSharedPtr interface)
Definition: master_plugin.cpp:124
canopen::ExternalSyncLayer::handleInit
virtual void handleInit(LayerStatus &status)
Definition: master_plugin.cpp:109
canopen::SyncLayer
Definition: canopen.h:305
canopen::ManagingSyncLayer::nodes_
std::set< void * > nodes_
Definition: master_plugin.cpp:14
canopen::ManagingSyncLayer::nodes_mutex_
boost::mutex nodes_mutex_
Definition: master_plugin.cpp:15
canopen::SyncCounter::properties
const SyncProperties properties
Definition: canopen.h:181
canopen::ExternalSyncLayer::reader_
can::BufferedReader reader_
Definition: master_plugin.cpp:96
canopen::SimpleMaster
WrapMaster< SimpleSyncLayer > SimpleMaster
Definition: master_plugin.cpp:134
can::Frame::data
std::array< value_type, 8 > data
canopen::SimpleSyncLayer::SimpleSyncLayer
SimpleSyncLayer(const SyncProperties &p, can::CommInterfaceSharedPtr interface)
Definition: master_plugin.cpp:84
canopen::Master::Allocator
Definition: canopen.h:320
canopen::SimpleSyncLayer::handleWrite
virtual void handleWrite(LayerStatus &status, const LayerState &current_state)
Definition: master_plugin.cpp:68
class_loader.hpp
canopen::SimpleSyncLayer::write_time_
time_point write_time_
Definition: master_plugin.cpp:45
canopen::Master
Definition: canopen.h:311
canopen::ExternalMaster
WrapMaster< ExternalSyncLayer > ExternalMaster
Definition: master_plugin.cpp:135
canopen
Definition: bcm_sync.h:8
canopen::WrapMaster::Allocator::allocate
virtual MasterSharedPtr allocate(const std::string &name, can::CommInterfaceSharedPtr interface)
Definition: master_plugin.cpp:128
canopen::ExternalSyncLayer::handleWrite
virtual void handleWrite(LayerStatus &status, const LayerState &current_state)
Definition: master_plugin.cpp:106
can::BufferedReader
canopen::Exception
Definition: exceptions.h:10
canopen::ManagingSyncLayer::step_
boost::chrono::milliseconds step_
Definition: master_plugin.cpp:12
canopen::ExternalSyncLayer
Definition: master_plugin.cpp:95
canopen::WrapMaster::interface_
can::CommInterfaceSharedPtr interface_
Definition: master_plugin.cpp:119
canopen::ManagingSyncLayer::interface_
can::CommInterfaceSharedPtr interface_
Definition: master_plugin.cpp:11
canopen::SyncProperties::header_
const can::Header header_
Definition: canopen.h:171
canopen::ManagingSyncLayer::handleShutdown
virtual void handleShutdown(LayerStatus &status)
Definition: master_plugin.cpp:18
canopen::get_abs_time
time_point get_abs_time(const time_duration &timeout)
Definition: canopen.h:20
canopen::ManagingSyncLayer::nodes_size_
std::atomic< size_t > nodes_size_
Definition: master_plugin.cpp:16
canopen::SimpleSyncLayer::handleRead
virtual void handleRead(LayerStatus &status, const LayerState &current_state)
Definition: master_plugin.cpp:62
canopen::SyncLayerSharedPtr
std::shared_ptr< SyncLayer > SyncLayerSharedPtr
Definition: canopen.h:309
canopen::SimpleSyncLayer::tryUpdateCounter
void tryUpdateCounter()
Definition: master_plugin.cpp:52
canopen::SimpleSyncLayer::read_time_
time_point read_time_
Definition: master_plugin.cpp:45
canopen::LayerStatus
Definition: layer.h:12
canopen::WrapMaster::Allocator
Definition: master_plugin.cpp:126
canopen::LayerReport
Definition: layer.h:48


canopen_master
Author(s): Mathias Lüdtke
autogenerated on Wed Mar 2 2022 00:52:26