canopen.h
Go to the documentation of this file.
1 #ifndef H_CANOPEN
2 #define H_CANOPEN
3 
7 #include "exceptions.h"
8 #include "layer.h"
9 #include "objdict.h"
10 #include "timer.h"
11 #include <stdexcept>
12 #include <boost/thread/condition_variable.hpp>
13 #include <boost/chrono/system_clocks.hpp>
14 #include <boost/lexical_cast.hpp>
15 
16 namespace canopen{
17 
19 typedef boost::chrono::high_resolution_clock::duration time_duration;
20 inline time_point get_abs_time(const time_duration& timeout) { return boost::chrono::high_resolution_clock::now() + timeout; }
21 inline time_point get_abs_time() { return boost::chrono::high_resolution_clock::now(); }
22 
23 
24 template<typename T> struct FrameOverlay: public can::Frame{
25  T &data;
26  FrameOverlay(const Header &h) : can::Frame(h,sizeof(T)), data(* (T*) can::Frame::c_array()) {
27  can::Frame::data.fill(0);
28  }
29  FrameOverlay(const can::Frame &f) : can::Frame(f), data(* (T*) can::Frame::c_array()) { }
30 };
31 
32 class SDOClient{
33 
35 
36  boost::timed_mutex mutex;
37 
39  bool processFrame(const can::Frame & msg);
40 
42  size_t offset;
43  size_t total;
44  bool done;
47 
48  void transmitAndWait(const canopen::ObjectDict::Entry &entry, const String &data, String *result);
49  void abort(uint32_t reason);
50 
52 protected:
53  void read(const canopen::ObjectDict::Entry &entry, String &data);
54  void write(const canopen::ObjectDict::Entry &entry, const String &data);
55 public:
57 
58  void init();
59 
60  SDOClient(const can::CommInterfaceSharedPtr interface, const ObjectDictSharedPtr dict, uint8_t node_id)
61  : interface_(interface), storage_(boost::make_shared<ObjectStorage>(dict, node_id, ObjectStorage::ReadDelegate(this, &SDOClient::read), ObjectStorage::WriteDelegate(this, &SDOClient::write))), reader_(false, 1)
62  {
63  }
64 };
65 
66 class PDOMapper{
67  boost::mutex mutex_;
68 
69  class Buffer{
70  public:
71  bool read(uint8_t* b, const size_t len);
72  void write(const uint8_t* b, const size_t len);
73  void read(const canopen::ObjectDict::Entry &entry, String &data);
74  void write(const canopen::ObjectDict::Entry &, const String &data);
75  void clean() { dirty = false; }
76  const size_t size;
77  Buffer(const size_t sz) : size(sz), dirty(false), empty(true), buffer(sz) {}
78 
79  private:
80  boost::mutex mutex;
81  bool dirty;
82  bool empty;
83  std::vector<char> buffer;
84  };
85  typedef boost::shared_ptr<Buffer> BufferSharedPtr;
86 
87  class PDO {
88  protected:
89  void parse_and_set_mapping(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index, const bool &read, const bool &write);
92  std::vector<BufferSharedPtr>buffers;
93  };
94 
95  struct TPDO: public PDO{
96  typedef boost::shared_ptr<TPDO> TPDOSharedPtr;
97  void sync();
98  static TPDOSharedPtr create(const can::CommInterfaceSharedPtr interface, const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index){
99  TPDOSharedPtr tpdo(new TPDO(interface));
100  if(!tpdo->init(storage, com_index, map_index))
101  tpdo.reset();
102  return tpdo;
103  }
104  private:
105  TPDO(const can::CommInterfaceSharedPtr interface) : interface_(interface){}
106  bool init(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index);
108  boost::mutex mutex;
109  };
110 
111  struct RPDO : public PDO{
112  void sync(LayerStatus &status);
113  typedef boost::shared_ptr<RPDO> RPDOSharedPtr;
114  static RPDOSharedPtr create(const can::CommInterfaceSharedPtr interface, const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index){
115  RPDOSharedPtr rpdo(new RPDO(interface));
116  if(!rpdo->init(storage, com_index, map_index))
117  rpdo.reset();
118  return rpdo;
119  }
120  private:
121  bool init(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index);
122  RPDO(const can::CommInterfaceSharedPtr interface) : interface_(interface), timeout(-1) {}
123  boost::mutex mutex;
125 
127  void handleFrame(const can::Frame & msg);
128  int timeout;
129  };
130 
131  boost::unordered_set<RPDO::RPDOSharedPtr> rpdos_;
132  boost::unordered_set<TPDO::TPDOSharedPtr> tpdos_;
133 
135 
136 public:
137  PDOMapper(const can::CommInterfaceSharedPtr interface);
138  void read(LayerStatus &status);
139  bool write();
140  bool init(const ObjectStorageSharedPtr storage, LayerStatus &status);
141 };
142 
143 class EMCYHandler : public Layer {
144  boost::atomic<bool> has_error_;
148  void handleEMCY(const can::Frame & msg);
150 
151  virtual void handleDiag(LayerReport &report);
152 
153  virtual void handleInit(LayerStatus &status);
154  virtual void handleRecover(LayerStatus &status);
155  virtual void handleRead(LayerStatus &status, const LayerState &current_state);
156  virtual void handleWrite(LayerStatus &status, const LayerState &current_state);
157  virtual void handleHalt(LayerStatus &status);
158  virtual void handleShutdown(LayerStatus &status);
159 
160 public:
161  EMCYHandler(const can::CommInterfaceSharedPtr interface, const ObjectStorageSharedPtr storage);
162  void resetErrors(LayerStatus &status);
163 };
164 
167  const uint16_t period_ms_;
168  const uint8_t overflow_;
169  SyncProperties(const can::Header &h, const uint16_t &p, const uint8_t &o) : header_(h), period_ms_(p), overflow_(o) {}
170  bool operator==(const SyncProperties &p) const { return p.header_ == (int) header_ && p.overflow_ == overflow_ && p.period_ms_ == period_ms_; }
171 
172 };
173 
174 class SyncCounter {
175 public:
177  SyncCounter(const SyncProperties &p) : properties(p) {}
178  virtual void addNode(void * const ptr) = 0;
179  virtual void removeNode(void * const ptr) = 0;
180  virtual ~SyncCounter() {}
181 };
182 typedef boost::shared_ptr<SyncCounter> SyncCounterSharedPtr;
183 
184 class Node : public Layer{
185 public:
186  enum State{
187  Unknown = 255, BootUp = 0, Stopped = 4, Operational = 5 , PreOperational = 127
188  };
189  const uint8_t node_id_;
190  Node(const can::CommInterfaceSharedPtr interface, const ObjectDictSharedPtr dict, uint8_t node_id, const SyncCounterSharedPtr sync = SyncCounterSharedPtr());
191 
192  const State getState();
193  void enterState(const State &s);
194 
195  const ObjectStorageSharedPtr getStorage() { return sdo_.storage_; }
196 
197  bool start();
198  bool stop();
199  bool reset();
200  bool reset_com();
201  bool prepare();
202 
206 
207  StateListenerConstSharedPtr addStateListener(const StateDelegate & s){
208  return state_dispatcher_.createListener(s);
209  }
210 
211  template<typename T> T get(const ObjectDict::Key& k){
212  return getStorage()->entry<T>(k).get();
213  }
214 
215 private:
216  virtual void handleDiag(LayerReport &report);
217 
218  virtual void handleInit(LayerStatus &status);
219  virtual void handleRecover(LayerStatus &status);
220  virtual void handleRead(LayerStatus &status, const LayerState &current_state);
221  virtual void handleWrite(LayerStatus &status, const LayerState &current_state);
222  virtual void handleHalt(LayerStatus &status);
223  virtual void handleShutdown(LayerStatus &status);
224 
225  template<typename T> int wait_for(const State &s, const T &timeout);
226 
227  boost::timed_mutex mutex;
228  boost::mutex cond_mutex;
229  boost::condition_variable cond;
230 
232  const SyncCounterSharedPtr sync_;
234 
236 
238 
239  void handleNMT(const can::Frame & msg);
240  void switchState(const uint8_t &s);
241 
245 
247  uint16_t getHeartbeatInterval() { return heartbeat_.valid()?heartbeat_.get_cached() : 0; }
248  void setHeartbeatInterval() { if(heartbeat_.valid()) heartbeat_.set(heartbeat_.desc().value().get<uint16_t>()); }
249  bool checkHeartbeat();
250 };
251 typedef boost::shared_ptr<Node> NodeSharedPtr;
252 
253 template<typename T> class Chain{
254 public:
255  typedef boost::shared_ptr<T> MemberSharedPtr;
256  void call(void (T::*func)(void)){
257  typename std::vector<MemberSharedPtr>::iterator it = elements.begin();
258  while(it != elements.end()){
259  ((**it).*func)();
260  ++it;
261  }
262  }
263  template<typename V> void call(void (T::*func)(const V&), const std::vector<V> &vs){
264  typename std::vector<MemberSharedPtr>::iterator it = elements.begin();
265  typename std::vector<V>::const_iterator it_v = vs.begin();
266  while(it_v != vs.end() && it != elements.end()){
267  ((**it).*func)(*it_v);
268  ++it; ++it_v;
269  }
270  }
271  template<typename V> void call(void (T::*func)(V&), std::vector<V> &vs){
272  vs.resize(elements.size());
273 
274  typename std::vector<MemberSharedPtr>::iterator it = elements.begin();
275  typename std::vector<V>::iterator it_v = vs.begin();
276  while(it_v != vs.end() && it != elements.end()){
277  ((**it).*func)(*it_v);
278  ++it; ++it_v;
279  }
280  }
281  void add(MemberSharedPtr t){
282  elements.push_back(t);
283  }
284 protected:
285  std::vector<MemberSharedPtr> elements;
286 };
287 
288 template<typename T> class NodeChain: public Chain<T>{
289 public:
290  const std::vector<typename Chain<T>::MemberSharedPtr>& getElements() { return Chain<T>::elements; }
291  void start() { this->call(&T::start); }
292  void stop() { this->call(&T::stop); }
293  void reset() { this->call(&T::reset); }
294  void reset_com() { this->call(&T::reset_com); }
295  void prepare() { this->call(&T::prepare); }
296 };
297 
298 class SyncLayer: public Layer, public SyncCounter{
299 public:
300  SyncLayer(const SyncProperties &p) : Layer("Sync layer"), SyncCounter(p) {}
301 };
302 typedef boost::shared_ptr<SyncLayer> SyncLayerSharedPtr;
303 
304 class Master: boost::noncopyable {
305 public:
306  virtual SyncLayerSharedPtr getSync(const SyncProperties &properties) = 0;
307  virtual ~Master() {}
308 
309  typedef boost::shared_ptr<Master> MasterSharedPtr;
310  class Allocator {
311  public:
312  virtual MasterSharedPtr allocate(const std::string &name, can::CommInterfaceSharedPtr interface) = 0;
313  virtual ~Allocator() {}
314  };
315 };
317 
318 class Settings
319 {
320 public:
321  template <typename T> T get_optional(const std::string &n, const T& def) const {
322  std::string repr;
323  if(!getRepr(n, repr)){
324  return def;
325  }
326  return boost::lexical_cast<T>(repr);
327  }
328  template <typename T> bool get(const std::string &n, T& val) const {
329  std::string repr;
330  if(!getRepr(n, repr)) return false;
331  val = boost::lexical_cast<T>(repr);
332  return true;
333  }
334  virtual ~Settings() {}
335 private:
336  virtual bool getRepr(const std::string &n, std::string & repr) const = 0;
337 };
338 
339 } // canopen
340 #endif // !H_CANOPEN
static RPDOSharedPtr create(const can::CommInterfaceSharedPtr interface, const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index)
Definition: canopen.h:114
boost::mutex mutex
Definition: canopen.h:123
const uint8_t overflow_
Definition: canopen.h:168
boost::shared_ptr< SyncCounter > SyncCounterSharedPtr
Definition: canopen.h:182
boost::shared_ptr< Buffer > BufferSharedPtr
Definition: canopen.h:85
const SyncProperties properties
Definition: canopen.h:176
ObjectStorage::Entry< ObjectStorage::DataType< ObjectDict::DEFTYPE_UNSIGNED16 >::type > heartbeat_
Definition: canopen.h:235
can::Frame last_msg
Definition: canopen.h:45
const can::CommInterfaceSharedPtr interface_
Definition: canopen.h:231
const ObjectDict::Entry & desc() const
Definition: objdict.h:438
virtual ~Settings()
Definition: canopen.h:334
can::Frame frame
Definition: canopen.h:90
ObjectStorage::Entry< uint8_t > num_errors_
Definition: canopen.h:146
const uint8_t node_id_
Definition: canopen.h:189
SyncCounter(const SyncProperties &p)
Definition: canopen.h:177
boost::shared_ptr< T > MemberSharedPtr
Definition: canopen.h:255
const can::Header header_
Definition: canopen.h:166
can::FrameListenerConstSharedPtr listener_
Definition: canopen.h:126
FrameOverlay(const Header &h)
Definition: canopen.h:26
boost::mutex mutex
Definition: canopen.h:80
boost::atomic< bool > has_error_
Definition: canopen.h:144
can::BufferedReader reader_
Definition: canopen.h:38
StateListenerConstSharedPtr addStateListener(const StateDelegate &s)
Definition: canopen.h:207
bool operator==(const SyncProperties &p) const
Definition: canopen.h:170
RPDO(const can::CommInterfaceSharedPtr interface)
Definition: canopen.h:122
boost::array< value_type, 8 > data
boost::timed_mutex mutex
Definition: canopen.h:36
StateListener::ListenerConstSharedPtr StateListenerConstSharedPtr
Definition: canopen.h:205
void call(void(T::*func)(V &), std::vector< V > &vs)
Definition: canopen.h:271
boost::shared_ptr< CommInterface > CommInterfaceSharedPtr
const can::CommInterfaceSharedPtr interface_
Definition: canopen.h:51
boost::shared_ptr< TPDO > TPDOSharedPtr
Definition: canopen.h:96
can::Listener< const StateDelegate, const State & > StateListener
Definition: canopen.h:204
can::FrameListenerConstSharedPtr emcy_listener_
Definition: canopen.h:147
boost::chrono::high_resolution_clock::time_point time_point
Definition: canopen.h:18
Buffer(const size_t sz)
Definition: canopen.h:77
const SyncCounterSharedPtr sync_
Definition: canopen.h:232
boost::chrono::high_resolution_clock::duration time_duration
Definition: canopen.h:19
SyncLayer(const SyncProperties &p)
Definition: canopen.h:300
const can::CommInterfaceSharedPtr interface_
Definition: canopen.h:107
const std::vector< typename Chain< T >::MemberSharedPtr > & getElements()
Definition: canopen.h:290
boost::shared_ptr< Node > NodeSharedPtr
Definition: canopen.h:251
virtual ~SyncCounter()
Definition: canopen.h:180
ObjectDict::ObjectDictSharedPtr ObjectDictSharedPtr
Definition: objdict.h:230
const ObjectStorageSharedPtr getStorage()
Definition: canopen.h:195
std::vector< BufferSharedPtr > buffers
Definition: canopen.h:92
FrameOverlay(const can::Frame &f)
Definition: canopen.h:29
const canopen::ObjectDict::Entry * current_entry
Definition: canopen.h:46
std::vector< MemberSharedPtr > elements
Definition: canopen.h:285
void call(void(T::*func)(const V &), const std::vector< V > &vs)
Definition: canopen.h:263
boost::mutex cond_mutex
Definition: canopen.h:228
const can::CommInterfaceSharedPtr interface_
Definition: canopen.h:124
can::Header client_id
Definition: canopen.h:34
boost::chrono::high_resolution_clock::time_point heartbeat_timeout_
Definition: canopen.h:246
uint8_t transmission_type
Definition: canopen.h:91
CommInterface::FrameListenerConstSharedPtr FrameListenerConstSharedPtr
fastdelegate::FastDelegate1< const State & > StateDelegate
Definition: canopen.h:203
value_type * c_array()
uint16_t getHeartbeatInterval()
Definition: canopen.h:247
boost::shared_ptr< Master > MasterSharedPtr
Definition: canopen.h:309
SDOClient sdo_
Definition: canopen.h:243
std::vector< char > buffer
Definition: canopen.h:83
SyncProperties(const can::Header &h, const uint16_t &p, const uint8_t &o)
Definition: canopen.h:169
boost::mutex mutex
Definition: canopen.h:108
const ObjectStorageSharedPtr storage_
Definition: canopen.h:149
const can::CommInterfaceSharedPtr interface_
Definition: canopen.h:134
void call(void(T::*func)(void))
Definition: canopen.h:256
can::FrameListenerConstSharedPtr nmt_listener_
Definition: canopen.h:233
Master::MasterSharedPtr MasterSharedPtr
Definition: canopen.h:316
void setHeartbeatInterval()
Definition: canopen.h:248
ObjectStorage::Entry< uint8_t > error_register_
Definition: canopen.h:145
PDOMapper pdo_
Definition: canopen.h:244
static TPDOSharedPtr create(const can::CommInterfaceSharedPtr interface, const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index)
Definition: canopen.h:98
boost::mutex mutex_
Definition: canopen.h:67
boost::condition_variable cond
Definition: canopen.h:229
boost::unordered_set< TPDO::TPDOSharedPtr > tpdos_
Definition: canopen.h:132
boost::shared_ptr< const Listener > ListenerConstSharedPtr
TPDO(const can::CommInterfaceSharedPtr interface)
Definition: canopen.h:105
T get_optional(const std::string &n, const T &def) const
Definition: canopen.h:321
void set(const T &val)
Definition: objdict.h:407
virtual ~Master()
Definition: canopen.h:307
time_point get_abs_time(const time_duration &timeout)
Definition: canopen.h:20
boost::shared_ptr< SyncLayer > SyncLayerSharedPtr
Definition: canopen.h:302
const uint16_t period_ms_
Definition: canopen.h:167
boost::shared_ptr< RPDO > RPDOSharedPtr
Definition: canopen.h:113
void add(MemberSharedPtr t)
Definition: canopen.h:281
ObjectStorage::ObjectStorageSharedPtr ObjectStorageSharedPtr
Definition: objdict.h:523
State state_
Definition: canopen.h:242
void reset_com()
Definition: canopen.h:294
can::SimpleDispatcher< StateListener > state_dispatcher_
Definition: canopen.h:237
const ObjectStorageSharedPtr storage_
Definition: canopen.h:56
boost::timed_mutex mutex
Definition: canopen.h:227
SDOClient(const can::CommInterfaceSharedPtr interface, const ObjectDictSharedPtr dict, uint8_t node_id)
Definition: canopen.h:60
boost::unordered_set< RPDO::RPDOSharedPtr > rpdos_
Definition: canopen.h:131


canopen_master
Author(s): Mathias Lüdtke
autogenerated on Sat May 4 2019 02:40:43