objdict.h
Go to the documentation of this file.
1 #ifndef H_OBJDICT
2 #define H_OBJDICT
3 
4 #include <list>
5 #include <memory>
6 #include <unordered_map>
7 #include <unordered_set>
8 
10 
11 #include <boost/thread/mutex.hpp>
12 #include <functional>
13 #include <typeinfo>
14 #include <vector>
15 #include "exceptions.h"
16 
17 namespace canopen{
18 
19 class TypeGuard{
20  const std::type_info& (*get_type)();
21  size_t type_size;
22 
23  template<typename T> class TypeInfo{
24  public:
25  static const std::type_info& id() { return typeid(T); }
26  };
27  TypeGuard(const std::type_info& (*ti)(), const size_t s): get_type(ti), type_size(s) {}
28 public:
29 
30  template<typename T> bool is_type() const {
31  return valid() && get_type() == typeid(T);
32  }
33 
34  bool operator==(const TypeGuard &other) const {
35  return valid() && other.valid() && (get_type() == other.get_type());
36  }
37 
38  TypeGuard(): get_type(0), type_size(0) {}
39  bool valid() const { return get_type != 0; }
40  size_t get_size() const { return type_size; }
41  template<typename T> static TypeGuard create() { return TypeGuard(TypeInfo<T>::id, sizeof(T)); }
42 };
43 
44 class String: public std::vector<char>{
45 public:
46  String() {}
47  String(const std::string &str) : std::vector<char>(str.begin(), str.end()) {}
48  operator const char * () const {
49  return &at(0);
50  }
51  operator const std::string () const {
52  return std::string(begin(), end());
53  }
54 };
55 
56 class HoldAny{
59  bool empty;
60 public:
61  HoldAny() : empty(true) {}
62 
63  const TypeGuard& type() const{ return type_guard; }
64 
65  template<typename T> HoldAny(const T &t) : type_guard(TypeGuard::create<T>()), empty(false){
66  buffer.resize(sizeof(T));
67  *(T*)&(buffer.front()) = t;
68  }
69  HoldAny(const std::string &t): type_guard(TypeGuard::create<std::string>()), empty(false){
70  if(!type_guard.is_type<std::string>()){
71  BOOST_THROW_EXCEPTION(std::bad_cast());
72  }
73  buffer = t;
74  }
75  HoldAny(const TypeGuard &t): type_guard(t), empty(true){ }
76 
77  bool is_empty() const { return empty; }
78 
79  const String& data() const {
80  if(empty){
81  BOOST_THROW_EXCEPTION(std::length_error("buffer empty"));
82  }
83  return buffer;
84  }
85 
86  template<typename T> const T & get() const{
87  if(!type_guard.is_type<T>()){
88  BOOST_THROW_EXCEPTION(std::bad_cast());
89  }else if(empty){
90  BOOST_THROW_EXCEPTION(std::length_error("buffer empty"));
91  }
92  return *(T*)&(buffer.front());
93  }
94 };
95 
96 template<> const String & HoldAny::get() const;
97 
98 struct DeviceInfo{
99  std::string vendor_name;
100  uint32_t vendor_number;
101  std::string product_name;
102  uint32_t product_number;
103  uint32_t revision_number;
104  std::string order_code;
105  std::unordered_set<uint32_t> baudrates;
108  uint8_t granularity;
111  uint16_t nr_of_rx_pdo;
112  uint16_t nr_of_tx_pdo;
114  std::unordered_set<uint16_t> dummy_usage;
115 };
116 
117 #define THROW_WITH_KEY(e,k) BOOST_THROW_EXCEPTION(boost::enable_error_info(e) << ObjectDict::key_info(k))
118 
120 protected:
121 public:
122  class Key{
123  static size_t fromString(const std::string &str);
124  public:
125  const size_t hash;
126  Key(const uint16_t i) : hash((i<<16)| 0xFFFF) {}
127  Key(const uint16_t i, const uint8_t s): hash((i<<16)| s) {}
128  Key(const std::string &str): hash(fromString(str)) {}
129  bool hasSub() const { return (hash & 0xFFFF) != 0xFFFF; }
130  uint8_t sub_index() const { return hash & 0xFFFF; }
131  uint16_t index() const { return hash >> 16;}
132  bool operator==(const Key &other) const { return hash == other.hash; }
133  operator std::string() const;
134  };
135  struct KeyHash {
136  std::size_t operator()(const Key& k) const { return k.hash; }
137  };
138 
139  enum Code{
140  NULL_DATA = 0x00,
141  DOMAIN_DATA = 0x02,
142  DEFTYPE = 0x05,
143  DEFSTRUCT = 0x06,
144  VAR = 0x07,
145  ARRAY = 0x08,
146  RECORD = 0x09
147  };
148  enum DataTypes{
149  DEFTYPE_INTEGER8 = 0x0002,
150  DEFTYPE_INTEGER16 = 0x0003,
151  DEFTYPE_INTEGER32 = 0x0004,
152  DEFTYPE_UNSIGNED8 = 0x0005,
153  DEFTYPE_UNSIGNED16 = 0x0006,
154  DEFTYPE_UNSIGNED32 = 0x0007,
155  DEFTYPE_REAL32 = 0x0008,
156  DEFTYPE_VISIBLE_STRING = 0x0009,
157  DEFTYPE_OCTET_STRING = 0x000A,
158  DEFTYPE_UNICODE_STRING = 0x000B,
159  DEFTYPE_DOMAIN = 0x000F,
160  DEFTYPE_REAL64 = 0x0010,
161  DEFTYPE_INTEGER64 = 0x0015,
162  DEFTYPE_UNSIGNED64 = 0x001B
163  };
164  struct Entry{
166  uint16_t index;
167  uint8_t sub_index;
168  uint16_t data_type;
169  bool constant;
170  bool readable;
171  bool writable;
172  bool mappable;
173  std::string desc;
176 
177  Entry() {}
178 
179  Entry(const Code c, const uint16_t i, const uint16_t t, const std::string & d, const bool r = true, const bool w = true, bool m = false, const HoldAny def = HoldAny(), const HoldAny init = HoldAny()):
180  obj_code(c), index(i), sub_index(0),data_type(t),readable(r), writable(w), mappable(m), desc(d), def_val(def), init_val(init) {}
181 
182  Entry(const uint16_t i, const uint8_t s, const uint16_t t, const std::string & d, const bool r = true, const bool w = true, bool m = false, const HoldAny def = HoldAny(), const HoldAny init = HoldAny()):
183  obj_code(VAR), index(i), sub_index(s),data_type(t),readable(r), writable(w), mappable(m), desc(d), def_val(def), init_val(init) {}
184 
185  operator Key() const { return Key(index, sub_index); }
186  const HoldAny & value() const { return !init_val.is_empty() ? init_val : def_val; }
187 
188  };
189  typedef std::shared_ptr<const Entry> EntryConstSharedPtr;
190 
191  const Entry& operator()(uint16_t i) const{
192  return *at(Key(i));
193  }
194  const Entry& operator()(uint16_t i, uint8_t s) const{
195  return *at(Key(i,s));
196  }
197  const EntryConstSharedPtr& get(const Key &k) const{
198  return at(k);
199  }
200  bool has(uint16_t i, uint8_t s) const{
201  return dict_.find(Key(i,s)) != dict_.end();
202  }
203  bool has(uint16_t i) const{
204  return dict_.find(Key(i)) != dict_.end();
205  }
206  bool has(const Key &k) const{
207  return dict_.find(k) != dict_.end();
208  }
209 
210  bool insert(bool is_sub, EntryConstSharedPtr e){
211  return dict_.insert(std::make_pair(is_sub?Key(e->index,e->sub_index):Key(e->index),e)).second;
212  }
213 
214  typedef std::unordered_map<Key, EntryConstSharedPtr, KeyHash> ObjectDictMap;
215  bool iterate(ObjectDictMap::const_iterator &it) const;
216  typedef std::list<std::pair<std::string, std::string> > Overlay;
217  typedef std::shared_ptr<ObjectDict> ObjectDictSharedPtr;
218  static ObjectDictSharedPtr fromFile(const std::string &path, const Overlay &overlay = Overlay());
220 
221  ObjectDict(const DeviceInfo &info): device_info(info) {}
222  typedef boost::error_info<struct tag_objectdict_key, ObjectDict::Key> key_info;
223 protected:
224  const EntryConstSharedPtr& at(const Key &key) const{
225  try{
226  return dict_.at(key);
227  }
228  catch(const std::out_of_range &e){
229  THROW_WITH_KEY(e, key);
230  }
231  }
232 
233  ObjectDictMap dict_;
234 };
236 typedef std::shared_ptr<const ObjectDict> ObjectDictConstSharedPtr;
237 
238 [[deprecated]]
239 std::size_t hash_value(ObjectDict::Key const& k);
240 
241 template<typename T> class NodeIdOffset{
243  T (*adder)(const uint8_t &, const T &);
244 
245  static T add(const uint8_t &u, const T &t) {
246  return u+t;
247  }
248 public:
249  NodeIdOffset(const T &t): offset(t), adder(add) {}
250 
251  static const T apply(const HoldAny &val, const uint8_t &u){
252  if(!val.is_empty()){
253  if(TypeGuard::create<T>() == val.type() ){
254  return val.get<T>();
255  }else{
256  const NodeIdOffset<T> &no = val.get< NodeIdOffset<T> >();
257  return no.adder(u, no.offset);
258  }
259  }else{
260  BOOST_THROW_EXCEPTION(std::bad_cast());
261  }
262 
263  }
264 };
265 
266 template<typename T> std::ostream& operator<<(std::ostream& stream, const NodeIdOffset<T> &n) {
267  //stream << "Offset: " << n.apply(0);
268  return stream;
269  }
270 std::ostream& operator<<(std::ostream& stream, const ObjectDict::Key &k);
271 
272 class AccessException : public Exception{
273 public:
274  AccessException(const std::string &w) : Exception(w) {}
275 };
276 
277 
279 public:
280  using ReadFunc = std::function<void(const ObjectDict::Entry&, String &)>;
281  using ReadDelegate [[deprecated("use ReadFunc instead")]] = can::DelegateHelper<ReadFunc>;
282 
283  using WriteFunc = std::function<void(const ObjectDict::Entry&, const String &)>;
284  using WriteDelegate [[deprecated("use WriteFunc instead")]] = can::DelegateHelper<WriteFunc>;
285 
286  typedef std::shared_ptr<ObjectStorage> ObjectStorageSharedPtr;
287 
288 protected:
289  class Data {
290  Data(const Data&) = delete; // prevent copies
291  Data& operator=(const Data&) = delete;
292 
293  boost::mutex mutex;
295  bool valid;
296 
299 
300  template <typename T> T & access(){
301  if(!valid){
302  THROW_WITH_KEY(std::length_error("buffer not valid"), key);
303  }
304  return *(T*)&(buffer.front());
305  }
306  template <typename T> T & allocate(){
307  if(!valid){
308  buffer.resize(sizeof(T));
309  valid = true;
310  }
311  return access<T>();
312  }
313  public:
317  size_t size() { boost::mutex::scoped_lock lock(mutex); return buffer.size(); }
318 
319  template<typename T> Data(const ObjectDict::Key &k, const ObjectDict::EntryConstSharedPtr &e, const T &val, const ReadFunc &r, const WriteFunc &w)
320  : valid(false), read_delegate(r), write_delegate(w), type_guard(TypeGuard::create<T>()), entry(e), key(k){
321  assert(r);
322  assert(w);
323  assert(e);
324  allocate<T>() = val;
325  }
326  Data(const ObjectDict::Key &k, const ObjectDict::EntryConstSharedPtr &e, const TypeGuard &t, const ReadFunc &r, const WriteFunc &w)
327  : valid(false), read_delegate(r), write_delegate(w), type_guard(t), entry(e), key(k){
328  assert(r);
329  assert(w);
330  assert(e);
331  assert(t.valid());
332  buffer.resize(t.get_size());
333  }
334  void set_delegates(const ReadFunc &r, const WriteFunc &w){
335  boost::mutex::scoped_lock lock(mutex);
336  if(r) read_delegate = r;
337  if(w) write_delegate = w;
338  }
339  template<typename T> const T get(bool cached) {
340  boost::mutex::scoped_lock lock(mutex);
341 
342  if(!entry->readable){
343  THROW_WITH_KEY(AccessException("no read access"), key);
344 
345  }
346 
347  if(entry->constant) cached = true;
348 
349  if(!valid || !cached){
350  allocate<T>();
351  read_delegate(*entry, buffer);
352  }
353  return access<T>();
354  }
355  template<typename T> void set(const T &val) {
356  boost::mutex::scoped_lock lock(mutex);
357 
358  if(!entry->writable){
359  if(access<T>() != val){
360  THROW_WITH_KEY(AccessException("no write access"), key);
361  }
362  }else{
363  allocate<T>() = val;
364  write_delegate(*entry, buffer);
365  }
366  }
367  template<typename T> void set_cached(const T &val) {
368  boost::mutex::scoped_lock lock(mutex);
369  if(!valid || val != access<T>() ){
370  if(!entry->writable){
371  THROW_WITH_KEY(AccessException("no write access and not cached"), key);
372  }else{
373  allocate<T>() = val;
374  write_delegate(*entry, buffer);
375  }
376  }
377  }
378  void init();
379  void reset();
380  void force_write();
381 
382  };
383  typedef std::shared_ptr<Data> DataSharedPtr;
384 public:
385  template<const uint16_t dt> struct DataType{
386  typedef void type;
387  };
388 
389  template<typename T> class Entry{
390  DataSharedPtr data;
391  public:
392  typedef T type;
393  bool valid() const { return data != 0; }
394  const T get() {
395  if(!data) BOOST_THROW_EXCEPTION( PointerInvalid("ObjectStorage::Entry::get()") );
396 
397  return data->get<T>(false);
398  }
399  bool get(T & val){
400  try{
401  val = get();
402  return true;
403  }catch(...){
404  return false;
405  }
406  }
407  const T get_cached() {
408  if(!data) BOOST_THROW_EXCEPTION( PointerInvalid("ObjectStorage::Entry::get_cached()") );
409 
410  return data->get<T>(true);
411  }
412  bool get_cached(T & val){
413  try{
414  val = get_cached();
415  return true;
416  }catch(...){
417  return false;
418  }
419  }
420  void set(const T &val) {
421  if(!data) BOOST_THROW_EXCEPTION( PointerInvalid("ObjectStorage::Entry::set(val)") );
422  data->set(val);
423  }
424  bool set_cached(const T &val) {
425  if(!data) return false;
426  try{
427  data->set_cached(val);
428  return true;
429  }catch(...){
430  return false;
431  }
432  }
433 
434  Entry() {}
435  Entry(DataSharedPtr &d)
436  : data(d){
437  assert(data);
438  }
439  Entry(ObjectStorageSharedPtr storage, uint16_t index)
440  : data(storage->entry<type>(index).data) {
441  assert(data);
442  }
443  Entry(ObjectStorageSharedPtr storage, uint16_t index, uint8_t sub_index)
444  : data(storage->entry<type>(index, sub_index).data) {
445  assert(data);
446  }
447  Entry(ObjectStorageSharedPtr storage, const ObjectDict::Key &k)
448  : data(storage->entry<type>(k).data) {
449  assert(data);
450  }
451  const ObjectDict::Entry & desc() const{
452  return *(data->entry);
453  }
454  };
455 
456  void reset();
457 
458 protected:
459  typedef std::unordered_map<ObjectDict::Key, DataSharedPtr, ObjectDict::KeyHash> ObjectStorageMap;
460  ObjectStorageMap storage_;
461  boost::mutex mutex_;
462 
463  void init_nolock(const ObjectDict::Key &key, const ObjectDict::EntryConstSharedPtr &entry);
464 
467  size_t map(const ObjectDict::EntryConstSharedPtr &e, const ObjectDict::Key &key, const ReadFunc & read_delegate, const WriteFunc & write_delegate);
468 public:
469  template<typename T> Entry<T> entry(const ObjectDict::Key &key){
470  boost::mutex::scoped_lock lock(mutex_);
471 
472  ObjectStorageMap::iterator it = storage_.find(key);
473 
474  if(it == storage_.end()){
475  const ObjectDict::EntryConstSharedPtr e = dict_->get(key);
476 
477  DataSharedPtr data;
478  TypeGuard type = TypeGuard::create<T>();
479 
480  if(!e->def_val.is_empty()){
481  T val = NodeIdOffset<T>::apply(e->def_val, node_id_);
482  data = std::make_shared<Data>(key, e,val, read_delegate_, write_delegate_);
483  }else{
484  if(!e->def_val.type().valid() || e->def_val.type() == type) {
485  data = std::make_shared<Data>(key,e,type, read_delegate_, write_delegate_);
486  }else{
487  THROW_WITH_KEY(std::bad_cast(), key);
488  }
489  }
490 
491  std::pair<ObjectStorageMap::iterator, bool> ok = storage_.insert(std::make_pair(key, data));
492  it = ok.first;
493  }
494 
495  if(!it->second->type_guard.is_type<T>()){
496  THROW_WITH_KEY(std::bad_cast(), key);
497  }
498  return Entry<T>(it->second);
499  }
500 
501  size_t map(uint16_t index, uint8_t sub_index, const ReadFunc & read_delegate, const WriteFunc & write_delegate);
502 
503  template<typename T> Entry<T> entry(uint16_t index){
504  return entry<T>(ObjectDict::Key(index));
505  }
506  template<typename T> Entry<T> entry(uint16_t index, uint8_t sub_index){
507  return entry<T>(ObjectDict::Key(index,sub_index));
508  }
509 
510  template<typename T> void entry(Entry<T> &e, uint16_t index){ // TODO: migrate to bool
511  e = entry<T>(ObjectDict::Key(index));
512  }
513  template<typename T> void entry(Entry<T> &e, uint16_t index, uint8_t sub_index){ // TODO: migrate to bool
514  e = entry<T>(ObjectDict::Key(index,sub_index));
515  }
516  template<typename T> bool entry(Entry<T> &e, const ObjectDict::Key &k){
517  try{
518  e = entry<T>(k);
519  return true;
520  }catch(...){
521  return false;
522  }
523  }
524  typedef std::function<std::string()> ReadStringFuncType;
525  ReadStringFuncType getStringReader(const ObjectDict::Key &key, bool cached = false);
526  typedef std::function<void(const std::string &)> WriteStringFuncType;
527  WriteStringFuncType getStringWriter(const ObjectDict::Key &key, bool cached = false);
528 
529  const ObjectDictConstSharedPtr dict_;
530  const uint8_t node_id_;
531 
532  ObjectStorage(ObjectDictConstSharedPtr dict, uint8_t node_id, ReadFunc read_delegate, WriteFunc write_delegate);
533 
534  void init(const ObjectDict::Key &key);
535  void init_all();
536 };
538 
539 template<> String & ObjectStorage::Data::access();
541 
542 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_INTEGER8> { typedef int8_t type;};
543 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_INTEGER16> { typedef int16_t type;};
544 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_INTEGER32> { typedef int32_t type;};
545 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_INTEGER64> { typedef int64_t type;};
546 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_UNSIGNED8> { typedef uint8_t type;};
547 
548 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_UNSIGNED16> { typedef uint16_t type;};
549 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_UNSIGNED32> { typedef uint32_t type;};
550 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_UNSIGNED64> { typedef uint64_t type;};
551 
552 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_REAL32> { typedef float type;};
553 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_REAL64> { typedef double type;};
554 
555 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_VISIBLE_STRING> { typedef String type;};
556 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_OCTET_STRING> { typedef String type;};
557 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_UNICODE_STRING> { typedef String type;};
558 template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_DOMAIN> { typedef String type;};
559 
560 template<typename T, typename R> static R *branch_type(const uint16_t data_type){
561  switch(ObjectDict::DataTypes(data_type)){
562  case ObjectDict::DEFTYPE_INTEGER8: return T::template func< ObjectDict::DEFTYPE_INTEGER8 >;
563  case ObjectDict::DEFTYPE_INTEGER16: return T::template func< ObjectDict::DEFTYPE_INTEGER16 >;
564  case ObjectDict::DEFTYPE_INTEGER32: return T::template func< ObjectDict::DEFTYPE_INTEGER32 >;
565  case ObjectDict::DEFTYPE_INTEGER64: return T::template func< ObjectDict::DEFTYPE_INTEGER64 >;
566 
567  case ObjectDict::DEFTYPE_UNSIGNED8: return T::template func< ObjectDict::DEFTYPE_UNSIGNED8 >;
568  case ObjectDict::DEFTYPE_UNSIGNED16: return T::template func< ObjectDict::DEFTYPE_UNSIGNED16 >;
569  case ObjectDict::DEFTYPE_UNSIGNED32: return T::template func< ObjectDict::DEFTYPE_UNSIGNED32 >;
570  case ObjectDict::DEFTYPE_UNSIGNED64: return T::template func< ObjectDict::DEFTYPE_UNSIGNED64 >;
571 
572  case ObjectDict::DEFTYPE_REAL32: return T::template func< ObjectDict::DEFTYPE_REAL32 >;
573  case ObjectDict::DEFTYPE_REAL64: return T::template func< ObjectDict::DEFTYPE_REAL64 >;
574 
575  case ObjectDict::DEFTYPE_VISIBLE_STRING: return T::template func< ObjectDict::DEFTYPE_VISIBLE_STRING >;
576  case ObjectDict::DEFTYPE_OCTET_STRING: return T::template func< ObjectDict::DEFTYPE_OCTET_STRING >;
577  case ObjectDict::DEFTYPE_UNICODE_STRING: return T::template func< ObjectDict::DEFTYPE_UNICODE_STRING >;
578  case ObjectDict::DEFTYPE_DOMAIN: return T::template func< ObjectDict::DEFTYPE_DOMAIN >;
579 
580  default:
581  throw std::bad_cast();
582  }
583 }
584 
585 } // canopen
586 
587 #endif // !H_OBJDICT
std::unordered_map< Key, EntryConstSharedPtr, KeyHash > ObjectDictMap
Definition: objdict.h:214
uint8_t sub_index() const
Definition: objdict.h:130
const uint8_t node_id_
Definition: objdict.h:530
static T add(const uint8_t &u, const T &t)
Definition: objdict.h:245
const ObjectDictConstSharedPtr dict_
Definition: objdict.h:529
Data(const ObjectDict::Key &k, const ObjectDict::EntryConstSharedPtr &e, const TypeGuard &t, const ReadFunc &r, const WriteFunc &w)
Definition: objdict.h:326
const ObjectDict::EntryConstSharedPtr entry
Definition: objdict.h:315
bool is_type() const
Definition: objdict.h:30
size_t type_size
Definition: objdict.h:21
const std::type_info &(* get_type)()
Definition: objdict.h:20
bool operator==(const TypeGuard &other) const
Definition: objdict.h:34
std::list< std::pair< std::string, std::string > > Overlay
Definition: objdict.h:216
std::unordered_set< uint32_t > baudrates
Definition: objdict.h:105
std::function< std::string()> ReadStringFuncType
Definition: objdict.h:524
uint32_t vendor_number
Definition: objdict.h:100
const TypeGuard type_guard
Definition: objdict.h:314
std::shared_ptr< const ObjectDict > ObjectDictConstSharedPtr
Definition: objdict.h:236
Entry< T > entry(uint16_t index)
Definition: objdict.h:503
Entry(ObjectStorageSharedPtr storage, uint16_t index, uint8_t sub_index)
Definition: objdict.h:443
void set_delegates(const ReadFunc &r, const WriteFunc &w)
Definition: objdict.h:334
std::shared_ptr< ObjectStorage > ObjectStorageSharedPtr
Definition: objdict.h:286
const T & get() const
Definition: objdict.h:86
Entry< T > entry(const ObjectDict::Key &key)
Definition: objdict.h:469
const TypeGuard & type() const
Definition: objdict.h:63
String buffer
Definition: objdict.h:57
std::shared_ptr< Data > DataSharedPtr
Definition: objdict.h:383
boost::mutex mutex_
Definition: objdict.h:461
static const T apply(const HoldAny &val, const uint8_t &u)
Definition: objdict.h:251
uint32_t product_number
Definition: objdict.h:102
std::size_t operator()(const Key &k) const
Definition: objdict.h:136
uint16_t index() const
Definition: objdict.h:131
bool dynamic_channels_supported
Definition: objdict.h:109
bool simple_boot_up_slave
Definition: objdict.h:107
Key(const std::string &str)
Definition: objdict.h:128
std::shared_ptr< const Entry > EntryConstSharedPtr
Definition: objdict.h:189
std::unordered_set< uint16_t > dummy_usage
Definition: objdict.h:114
String(const std::string &str)
Definition: objdict.h:47
const HoldAny & value() const
Definition: objdict.h:186
const Entry & operator()(uint16_t i) const
Definition: objdict.h:191
bool valid() const
Definition: objdict.h:39
void set_cached(const T &val)
Definition: objdict.h:367
Entry(const Code c, const uint16_t i, const uint16_t t, const std::string &d, const bool r=true, const bool w=true, bool m=false, const HoldAny def=HoldAny(), const HoldAny init=HoldAny())
Definition: objdict.h:179
uint32_t revision_number
Definition: objdict.h:103
bool has(const Key &k) const
Definition: objdict.h:206
bool is_empty() const
Definition: objdict.h:77
uint8_t granularity
Definition: objdict.h:108
uint16_t nr_of_rx_pdo
Definition: objdict.h:111
ObjectDict::ObjectDictSharedPtr ObjectDictSharedPtr
Definition: objdict.h:235
bool operator==(const Key &other) const
Definition: objdict.h:132
Key(const uint16_t i, const uint8_t s)
Definition: objdict.h:127
WriteFunc write_delegate_
Definition: objdict.h:466
static R * branch_type(const uint16_t data_type)
Definition: objdict.h:560
const size_t hash
Definition: objdict.h:125
ObjectDict(const DeviceInfo &info)
Definition: objdict.h:221
size_t get_size() const
Definition: objdict.h:40
uint16_t nr_of_tx_pdo
Definition: objdict.h:112
ReadFunc read_delegate_
Definition: objdict.h:465
std::unordered_map< ObjectDict::Key, DataSharedPtr, ObjectDict::KeyHash > ObjectStorageMap
Definition: objdict.h:459
ObjectStorageMap storage_
Definition: objdict.h:460
bool simple_boot_up_master
Definition: objdict.h:106
const Entry & operator()(uint16_t i, uint8_t s) const
Definition: objdict.h:194
bool set_cached(const T &val)
Definition: objdict.h:424
bool has(uint16_t i, uint8_t s) const
Definition: objdict.h:200
std::string vendor_name
Definition: objdict.h:99
const EntryConstSharedPtr & at(const Key &key) const
Definition: objdict.h:224
static const std::type_info & id()
Definition: objdict.h:25
Entry(ObjectStorageSharedPtr storage, const ObjectDict::Key &k)
Definition: objdict.h:447
std::size_t hash_value(ObjectDict::Key const &k)
Definition: objdict.cpp:9
Data(const ObjectDict::Key &k, const ObjectDict::EntryConstSharedPtr &e, const T &val, const ReadFunc &r, const WriteFunc &w)
Definition: objdict.h:319
std::shared_ptr< ObjectDict > ObjectDictSharedPtr
Definition: objdict.h:217
Entry< T > entry(uint16_t index, uint8_t sub_index)
Definition: objdict.h:506
void entry(Entry< T > &e, uint16_t index)
Definition: objdict.h:510
const ObjectDict::Entry & desc() const
Definition: objdict.h:451
TypeGuard type_guard
Definition: objdict.h:58
const DeviceInfo device_info
Definition: objdict.h:219
bool insert(bool is_sub, EntryConstSharedPtr e)
Definition: objdict.h:210
void entry(Entry< T > &e, uint16_t index, uint8_t sub_index)
Definition: objdict.h:513
TypeGuard(const std::type_info &(*ti)(), const size_t s)
Definition: objdict.h:27
HoldAny(const std::string &t)
Definition: objdict.h:69
Entry(DataSharedPtr &d)
Definition: objdict.h:435
const ObjectDict::Key key
Definition: objdict.h:316
HoldAny(const T &t)
Definition: objdict.h:65
ObjectDictMap dict_
Definition: objdict.h:233
#define THROW_WITH_KEY(e, k)
Definition: objdict.h:117
std::string order_code
Definition: objdict.h:104
std::function< void(const ObjectDict::Entry &, const String &)> WriteFunc
Definition: objdict.h:283
bool hasSub() const
Definition: objdict.h:129
std::ostream & operator<<(std::ostream &stream, const NodeIdOffset< T > &n)
Definition: objdict.h:266
AccessException(const std::string &w)
Definition: objdict.h:274
HoldAny(const TypeGuard &t)
Definition: objdict.h:75
static TypeGuard create()
Definition: objdict.h:41
std::function< void(const std::string &)> WriteStringFuncType
Definition: objdict.h:526
Entry(ObjectStorageSharedPtr storage, uint16_t index)
Definition: objdict.h:439
ObjectStorage::ObjectStorageSharedPtr ObjectStorageSharedPtr
Definition: objdict.h:537
boost::error_info< struct tag_objectdict_key, ObjectDict::Key > key_info
Definition: objdict.h:222
std::string product_name
Definition: objdict.h:101
T(* adder)(const uint8_t &, const T &)
Definition: objdict.h:243
bool entry(Entry< T > &e, const ObjectDict::Key &k)
Definition: objdict.h:516
Entry(const uint16_t i, const uint8_t s, const uint16_t t, const std::string &d, const bool r=true, const bool w=true, bool m=false, const HoldAny def=HoldAny(), const HoldAny init=HoldAny())
Definition: objdict.h:182
NodeIdOffset(const T &t)
Definition: objdict.h:249
bool has(uint16_t i) const
Definition: objdict.h:203
std::function< void(const ObjectDict::Entry &, String &)> ReadFunc
Definition: objdict.h:280
Key(const uint16_t i)
Definition: objdict.h:126
const String & data() const
Definition: objdict.h:79


canopen_master
Author(s): Mathias Lüdtke
autogenerated on Mon Feb 28 2022 23:28:03