objdict.cpp
Go to the documentation of this file.
3 #include <boost/property_tree/ptree.hpp>
4 #include <boost/property_tree/ini_parser.hpp>
5 #include <boost/lexical_cast.hpp>
6 #include <boost/algorithm/string.hpp>
7 
8 namespace canopen{
9  size_t hash_value(ObjectDict::Key const& k) { return k.hash; }
10  std::ostream& operator<<(std::ostream& stream, const ObjectDict::Key &k) { return stream << std::string(k); }
11 }
12 
13 using namespace canopen;
14 
15 template<> const String & HoldAny::get() const{
16  return buffer;
17 }
18 
20  if(!valid){
21  THROW_WITH_KEY(std::length_error("buffer not valid") , key);
22  }
23  return buffer;
24 }
26  buffer.resize(0);
27  valid = true;
28  return buffer;
29 }
30 
31 size_t ObjectDict::Key::fromString(const std::string &str){
32  uint16_t index = 0;
33  uint8_t sub_index = 0;
34  int num = sscanf(str.c_str(),"%hxsub%hhx", &index, &sub_index);
35  return (index << 16) | (num==2?sub_index:0xFFFF);
36 }
37 ObjectDict::Key::operator std::string() const{
38  std::stringstream sstr;
39  sstr << std::hex << index();
40  if(hasSub()) sstr << "sub" << (int) sub_index();
41  return sstr.str();
42 }
44  boost::mutex::scoped_lock lock(mutex);
45 
46  if(entry->init_val.is_empty()) return;
47 
48  if(valid && !entry->def_val.is_empty() && buffer != entry->def_val.data()) return; // buffer was changed
49 
50  if(!valid || buffer != entry->init_val.data()){
51  buffer = entry->init_val.data();
52  valid = true;
53  if(entry->writable && (entry->def_val.is_empty() || entry->init_val.data() != entry->def_val.data()))
54  write_delegate(*entry, buffer);
55  }
56 }
58  boost::mutex::scoped_lock lock(mutex);
59 
60  if(!valid && entry->readable){
61  read_delegate(*entry, buffer);
62  valid = true;
63  }
64  if(valid) write_delegate(*entry, buffer);
65 }
66 
68  boost::mutex::scoped_lock lock(mutex);
69  if(!entry->def_val.is_empty() && entry->def_val.type() == type_guard){
70  buffer = entry->def_val.data();
71  valid = true;
72  }else{
73  valid = false;
74  }
75 }
76 
77 bool ObjectDict::iterate(ObjectDict::ObjectDictMap::const_iterator &it) const{
78  if(it != ObjectDict::ObjectDictMap::const_iterator()){
79  ++it;
80  }else it = dict_.begin();
81  return it != dict_.end();
82 }
83 void set_access( ObjectDict::Entry &entry, std::string access){
84  boost::algorithm::to_lower(access);
85  entry.constant = false;
86  if(access == "ro"){
87  entry.readable = true;
88  entry.writable = false;
89  }else if (access == "wo"){
90  entry.readable = false;
91  entry.writable = true;
92  }else if (access == "rw"){
93  entry.readable = true;
94  entry.writable = true;
95  }else if (access == "rwr"){
96  entry.readable = true;
97  entry.writable = true;
98  }else if (access == "rww"){
99  entry.readable = true;
100  entry.writable = true;
101  }else if (access == "const"){
102  entry.readable = true;
103  entry.writable = false;
104  entry.constant = true;
105  }else{
106  THROW_WITH_KEY(ParseException("Cannot determine access"), ObjectDict::Key(entry));
107  }
108 }
109 
110 template<typename T> T int_from_string(const std::string &s);
111 
112 template<> int8_t int_from_string(const std::string &s){
113  return strtol(s.c_str(), 0, 0);
114 }
115 template<> uint8_t int_from_string(const std::string &s){
116  return strtoul(s.c_str(), 0, 0);
117 }
118 template<> int16_t int_from_string(const std::string &s){
119  return strtol(s.c_str(), 0, 0);
120 }
121 template<> uint16_t int_from_string(const std::string &s){
122  return strtoul(s.c_str(), 0, 0);
123 }
124 template<> int32_t int_from_string(const std::string &s){
125  return strtol(s.c_str(), 0, 0);
126 }
127 template<> uint32_t int_from_string(const std::string &s){
128  return strtoul(s.c_str(), 0, 0);
129 }
130 
131 template<> int64_t int_from_string(const std::string &s){
132  return strtoll(s.c_str(), 0, 0);
133 }
134 template<> uint64_t int_from_string(const std::string &s){
135  return strtoull(s.c_str(), 0, 0);
136 }
137 
138 template<typename T> HoldAny parse_int(boost::property_tree::iptree &pt, const std::string &key){
139  if(pt.count(key) == 0) return HoldAny(TypeGuard::create<T>());
140 
141  std::string str = boost::trim_copy(pt.get<std::string>(key));
142  if(boost::istarts_with(str,"$NODEID")){
143  return HoldAny(NodeIdOffset<T>(int_from_string<T>(boost::trim_copy(str.substr(str.find("+",7)+1)))));
144  }else return HoldAny(int_from_string<T>(str));
145 }
146 
147 template<typename T> HoldAny parse_octets(boost::property_tree::iptree &pt, const std::string &key){
148  std::string out;
149  if(pt.count(key) == 0 || can::hex2buffer(out,pt.get<std::string>(key), true)) return HoldAny(TypeGuard::create<T>());
150  return HoldAny(T(out));
151 }
152 
153 template<typename T> HoldAny parse_typed_value(boost::property_tree::iptree &pt, const std::string &key){
154  if(pt.count(key) == 0) return HoldAny(TypeGuard::create<T>());
155  return HoldAny(pt.get<T>(key));
156 }
157 template<> HoldAny parse_typed_value<String>(boost::property_tree::iptree &pt, const std::string &key){
158  if(pt.count(key) == 0) return HoldAny(TypeGuard::create<String>());
159  return HoldAny(String(pt.get<std::string>(key)));
160 }
161 
163  template<const ObjectDict::DataTypes dt> static HoldAny func(boost::property_tree::iptree &pt, const std::string &key);
164  static HoldAny read_value(boost::property_tree::iptree &pt, uint16_t data_type, const std::string &key){
165  return branch_type<ReadAnyValue, HoldAny (boost::property_tree::iptree &, const std::string &)>(data_type)(pt, key);
166  }
167 };
168 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_INTEGER8>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<int8_t>(pt,key); }
169 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_INTEGER16>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<int16_t>(pt,key); }
170 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_INTEGER32>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<int32_t>(pt,key); }
171 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_INTEGER64>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<int64_t>(pt,key); }
172 
173 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_UNSIGNED8>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<uint8_t>(pt,key); }
174 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_UNSIGNED16>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<uint16_t>(pt,key); }
175 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_UNSIGNED32>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<uint32_t>(pt,key); }
176 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_UNSIGNED64>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<uint64_t>(pt,key); }
177 
178 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_DOMAIN>(boost::property_tree::iptree &pt, const std::string &key)
179 { return parse_octets<ObjectStorage::DataType<ObjectDict::DEFTYPE_DOMAIN>::type>(pt,key); }
180 
181 template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_OCTET_STRING>(boost::property_tree::iptree &pt, const std::string &key)
182 { return parse_octets<ObjectStorage::DataType<ObjectDict::DEFTYPE_OCTET_STRING>::type>(pt,key); }
183 
184 template<const ObjectDict::DataTypes dt> HoldAny ReadAnyValue::func(boost::property_tree::iptree &pt, const std::string &key){
185  return parse_typed_value<typename ObjectStorage::DataType<dt>::type>(pt, key);
186 }
187 
188 template<typename T> void read_optional(T& var, boost::property_tree::iptree &pt, const std::string &key){
189  var = pt.get(key, T());
190 }
191 
192 template<typename T> void read_integer(T& var, boost::property_tree::iptree &pt, const std::string &key){
193  var = int_from_string<T>(pt.get<std::string>(key));
194 }
195 
196 template<typename T> T read_integer(boost::property_tree::iptree &pt, const std::string &key){
197  return int_from_string<T>(pt.get<std::string>(key, std::string()));
198 }
199 
200 
201 void read_var(ObjectDict::Entry &entry, boost::property_tree::iptree &object){
202  read_integer<uint16_t>(entry.data_type, object, "DataType");
203  entry.mappable = object.get<bool>("PDOMapping", false);
204  try{
205  set_access(entry, object.get<std::string>("AccessType"));
206  }
207  catch(...){
208  THROW_WITH_KEY(ParseException("No AccessType") , ObjectDict::Key(entry));
209 
210  }
211  entry.def_val = ReadAnyValue::read_value(object, entry.data_type, "DefaultValue");
212  entry.init_val = ReadAnyValue::read_value(object, entry.data_type, "ParameterValue");
213 }
214 
215 void parse_object(ObjectDictSharedPtr dict, boost::property_tree::iptree &pt, const std::string &name, const uint8_t* sub_index = 0){
216  boost::optional<boost::property_tree::iptree&> object = pt.get_child_optional(name.substr(2));
217  if(!object) return;
218 
219  std::shared_ptr<ObjectDict::Entry> entry = std::make_shared<ObjectDict::Entry>();
220  try{
221  entry->index = int_from_string<uint16_t>(name);
222  entry->obj_code = ObjectDict::Code(int_from_string<uint16_t>(object->get<std::string>("ObjectType", boost::lexical_cast<std::string>((uint16_t)ObjectDict::VAR))));
223  entry->desc = object->get<std::string>("Denotation",object->get<std::string>("ParameterName"));
224 
225  // std::cout << name << ": "<< entry->desc << std::endl;
226  if(entry->obj_code == ObjectDict::VAR || entry->obj_code == ObjectDict::DOMAIN_DATA || sub_index){
227  entry->sub_index = sub_index? *sub_index: 0;
228  read_var(*entry, *object);
229  dict->insert(sub_index != 0, entry);
230  }else if(entry->obj_code == ObjectDict::ARRAY || entry->obj_code == ObjectDict::RECORD){
231  uint8_t subs = read_integer<uint8_t>(*object, "CompactSubObj");
232  if(subs){ // compact
233  dict->insert(true, std::make_shared<const canopen::ObjectDict::Entry>(entry->index, 0, ObjectDict::DEFTYPE_UNSIGNED8, "NrOfObjects", true, false, false, HoldAny(subs)));
234 
235  read_var(*entry, *object);
236 
237  for(uint8_t i=1; i< subs; ++i){
238  std::string subname = pt.get<std::string>(name.substr(2)+"Name." + boost::lexical_cast<std::string>((int)i),entry->desc + boost::lexical_cast<std::string>((int)i));
239  subname = pt.get<std::string>(name.substr(2)+"Denotation." + boost::lexical_cast<std::string>((int)i), subname);
240 
241  dict->insert(true, std::make_shared<const canopen::ObjectDict::Entry>(entry->index, i, entry->data_type, name, entry->readable, entry->writable, entry->mappable, entry->def_val,
242  ReadAnyValue::read_value(pt, entry->data_type, name.substr(2)+"Value." + boost::lexical_cast<std::string>((int)i))));
243  }
244  }else{
245  read_integer(subs, *object, "SubNumber");
246  for(uint8_t i=0; i< subs; ++i){
247  std::stringstream buf;
248  buf << name << "sub" << std::hex << int(i);
249  // std::cout << "added " << buf.str() << " " << int(i) << std::endl;
250  parse_object(dict, pt, buf.str(), &i);
251  }
252  }
253  }else{
254  THROW_WITH_KEY(ParseException("Object type not supported") , ObjectDict::Key(*entry));
255  }
256  }
257  catch(const std::bad_cast &e){
258  throw ParseException(std::string("Type of ") + name + " does not match or is not supported");
259  }
260  catch(const std::exception&e){
261  throw ParseException(std::string("Cannot process ") + name + ": " + e.what());
262  }
263 }
264 void parse_objects(ObjectDictSharedPtr dict, boost::property_tree::iptree &pt, const std::string &key){
265  if(!pt.count(key)) return;
266 
267  boost::property_tree::iptree objects = pt.get_child(key);
268  uint16_t count = read_integer<uint16_t>(objects, "SupportedObjects");
269  for(uint16_t i=0; i < count; ++i){
270  std::string name = objects.get<std::string>(boost::lexical_cast<std::string>(i+1));
271  parse_object(dict, pt, name);
272  }
273 }
274 ObjectDictSharedPtr ObjectDict::fromFile(const std::string &path, const ObjectDict::Overlay &overlay){
275  DeviceInfo info;
276  boost::property_tree::iptree pt;
277  ObjectDictSharedPtr dict;
278 
279  boost::property_tree::read_ini(path, pt);
280 
281  boost::property_tree::iptree di = pt.get_child("DeviceInfo");
282 
283  read_optional(info.vendor_name, di, "VendorName");
284  read_optional(info.vendor_number, di, "VendorNumber");
285  read_optional(info.product_name, di, "ProductName");
286  read_optional(info.product_number, di, "ProductNumber");
287  read_optional(info.revision_number, di, "RevisionNumber");
288  read_optional(info.order_code, di, "OrderCode");
289  read_optional(info.simple_boot_up_master, di, "SimpleBootUpMaster");
290  read_optional(info.simple_boot_up_slave, di, "SimpleBootUpSlave");
291  read_optional(info.granularity, di, "Granularity");
292  read_optional(info.dynamic_channels_supported, di, "DynamicChannelsSupported");
293  read_optional(info.group_messaging, di, "GroupMessaging");
294  read_optional(info.nr_of_rx_pdo, di, "NrOfRXPDO");
295  read_optional(info.nr_of_tx_pdo, di, "NrOfTXPDO");
296  read_optional(info.lss_supported, di, "LSS_Supported");
297 
298  std::unordered_set<uint32_t> baudrates;
299  std::unordered_set<uint16_t> dummy_usage;
300 
301  for(boost::property_tree::iptree::value_type &v: di){
302  if(v.first.find("BaudRate_") == 0){
303  uint16_t rate = int_from_string<uint16_t>(v.first.substr(9));
304  if(v.second.get_value<bool>())
305  info.baudrates.insert(rate * 1000);
306  }
307  }
308 
309  if(pt.count("DummyUsage")){
310  for(boost::property_tree::iptree::value_type &v: pt.get_child("DummyUsage")){
311  if(v.first.find("Dummy") == 0){
312  // std::cout << ("0x"+v.first.substr(5)) << std::endl;
313  uint16_t dummy = int_from_string<uint16_t>("0x"+v.first.substr(5));
314  if(v.second.get_value<bool>())
315  info.dummy_usage.insert(dummy);
316  }
317  }
318  }
319 
320  dict = std::make_shared<ObjectDict>(info);
321 
322  for(Overlay::const_iterator it= overlay.begin(); it != overlay.end(); ++it){
323  pt.get_child(it->first).put("ParameterValue", it->second);
324  }
325 
326  parse_objects(dict, pt, "MandatoryObjects");
327  parse_objects(dict, pt, "OptionalObjects");
328  parse_objects(dict, pt, "ManufacturerObjects");
329 
330  return dict;
331 }
332 
333 size_t ObjectStorage::map(const ObjectDict::EntryConstSharedPtr &e, const ObjectDict::Key &key, const ReadFunc & read_delegate, const WriteFunc & write_delegate){
334  ObjectStorageMap::iterator it = storage_.find(key);
335 
336  if(it == storage_.end()){
337 
339 
340 
341  if(!e->def_val.type().valid()){
342  THROW_WITH_KEY(std::bad_cast() , key);
343  }
344 
345  data = std::make_shared<Data>(key, e,e->def_val.type(),read_delegate_, write_delegate_);
346 
347  std::pair<ObjectStorageMap::iterator, bool> ok = storage_.insert(std::make_pair(key, data));
348  it = ok.first;
349  it->second->reset();
350 
351  }
352 
353  if(read_delegate && write_delegate){
354  it->second->set_delegates(read_delegate_, write_delegate);
355  it->second->force_write(); // update buffer
356  it->second->set_delegates(read_delegate, write_delegate_);
357  }else if(write_delegate) {
358  it->second->set_delegates(read_delegate_, write_delegate);
359  it->second->force_write(); // update buffer
360  }else if(read_delegate){
361  it->second->set_delegates(read_delegate, write_delegate_);
362  }
363  return it->second->size();
364 }
365 
366 size_t ObjectStorage::map(uint16_t index, uint8_t sub_index, const ReadFunc & read_delegate, const WriteFunc & write_delegate){
367  boost::mutex::scoped_lock lock(mutex_);
368 
369  try{
370  ObjectDict::Key key(index,sub_index);
371  const ObjectDict::EntryConstSharedPtr e = dict_->get(key);
372  return map(e, key,read_delegate, write_delegate);
373  }
374  catch(std::out_of_range) {
375  if(sub_index != 0) throw;
376 
377  ObjectDict::Key key(index);
378  const ObjectDict::EntryConstSharedPtr e = dict_->get(key);
379  return map(e, key, read_delegate, write_delegate);
380  }
381 }
382 
383 ObjectStorage::ObjectStorage(ObjectDictConstSharedPtr dict, uint8_t node_id, ReadFunc read_delegate, WriteFunc write_delegate)
384 :read_delegate_(read_delegate), write_delegate_(write_delegate), dict_(dict), node_id_(node_id){
385  assert(dict_);
386  assert(read_delegate_);
387  assert(write_delegate_);
388 }
389 
391 
392  if(!entry->init_val.is_empty()){
393  ObjectStorageMap::iterator it = storage_.find(key);
394 
395  if(it == storage_.end()){
396  DataSharedPtr data = std::make_shared<Data>(key,entry, entry->init_val.type(), read_delegate_, write_delegate_);
397  std::pair<ObjectStorageMap::iterator, bool> ok = storage_.insert(std::make_pair(key, data));
398  it = ok.first;
399  if(!ok.second){
400  THROW_WITH_KEY(std::bad_alloc() , key);
401  }
402  }
403  it->second->init();
404  }
405 }
407  boost::mutex::scoped_lock lock(mutex_);
408  init_nolock(key, dict_->get(key));
409 }
411  boost::mutex::scoped_lock lock(mutex_);
412 
413  ObjectDict::ObjectDictMap::const_iterator entry_it;
414  while(dict_->iterate(entry_it)){
415  init_nolock(entry_it->first, entry_it->second);
416  }
417 }
418 
420  boost::mutex::scoped_lock lock(mutex_);
421  for(ObjectStorageMap::iterator it = storage_.begin(); it != storage_.end(); ++it){
422  it->second->reset();
423  }
424 }
425 
426 template<const ObjectDict::DataTypes dt, typename T> std::string formatValue(const T &value){
427  std::stringstream sstr;
428  sstr << value;
429  return sstr.str();
430 }
431 template<> std::string formatValue<ObjectDict::DEFTYPE_DOMAIN>(const std::string &value){
432  return can::buffer2hex(value, false);
433 }
434 template<> std::string formatValue<ObjectDict::DEFTYPE_OCTET_STRING>(const std::string &value){
435  return can::buffer2hex(value, false);
436 }
437 
438 struct PrintValue {
439  template<const ObjectDict::DataTypes dt> static std::string func(ObjectStorage& storage, const ObjectDict::Key &key, bool cached){
441  return formatValue<dt>(cached? entry.get_cached() : entry.get() );
442  }
443  static std::function<std::string()> getReader(ObjectStorage& storage, const ObjectDict::Key &key, bool cached){
444  ObjectDict::DataTypes data_type = (ObjectDict::DataTypes) storage.dict_->get(key)->data_type;
445  return std::bind(branch_type<PrintValue, std::string (ObjectStorage&, const ObjectDict::Key &, bool)>(data_type),std::ref(storage), key, cached);
446  }
447 };
448 
450  return PrintValue::getReader(*this, key, cached);
451 }
452 
454  typedef HoldAny (*reader_type)(boost::property_tree::iptree &, const std::string &);
455  template<typename T> static void write(ObjectStorage::Entry<T> entry, bool cached, reader_type reader, const std::string &value){
456  boost::property_tree::iptree pt;
457  pt.put("value", value);
458  HoldAny any = reader(pt, "value");
459  if(cached){
460  entry.set_cached(any.get<T>());
461  } else {
462  entry.set(any.get<T>());
463  }
464  }
465  template<const ObjectDict::DataTypes dt> static std::function<void (const std::string&)> func(ObjectStorage& storage, const ObjectDict::Key &key, bool cached){
467  reader_type reader = branch_type<ReadAnyValue, HoldAny (boost::property_tree::iptree &, const std::string &)>(dt);
468  return std::bind(&WriteStringValue::write<typename ObjectStorage::DataType<dt>::type >, entry, cached, reader, std::placeholders::_1);
469  }
470  static std::function<void (const std::string&)> getWriter(ObjectStorage& storage, const ObjectDict::Key &key, bool cached){
471  ObjectDict::DataTypes data_type = (ObjectDict::DataTypes) storage.dict_->get(key)->data_type;
472  return branch_type<WriteStringValue, std::function<void (const std::string&)> (ObjectStorage&, const ObjectDict::Key &, bool)>(data_type)(storage, key, cached);
473  }
474 };
475 
477  return WriteStringValue::getWriter(*this, key, cached);
478 }
T int_from_string(const std::string &s)
Definition: objdict.cpp:112
const ObjectDictConstSharedPtr dict_
Definition: objdict.h:529
void read_optional(T &var, boost::property_tree::iptree &pt, const std::string &key)
Definition: objdict.cpp:188
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
std::shared_ptr< const ObjectDict > ObjectDictConstSharedPtr
Definition: objdict.h:236
void init(const ObjectDict::Key &key)
Definition: objdict.cpp:406
const T & get() const
Definition: objdict.h:86
Entry< T > entry(const ObjectDict::Key &key)
Definition: objdict.h:469
String buffer
Definition: objdict.h:57
std::shared_ptr< Data > DataSharedPtr
Definition: objdict.h:383
boost::mutex mutex_
Definition: objdict.h:461
uint32_t product_number
Definition: objdict.h:102
static std::function< std::string()> getReader(ObjectStorage &storage, const ObjectDict::Key &key, bool cached)
Definition: objdict.cpp:443
static std::string func(ObjectStorage &storage, const ObjectDict::Key &key, bool cached)
Definition: objdict.cpp:439
static void write(ObjectStorage::Entry< T > entry, bool cached, reader_type reader, const std::string &value)
Definition: objdict.cpp:455
static ObjectDictSharedPtr fromFile(const std::string &path, const Overlay &overlay=Overlay())
Definition: objdict.cpp:274
HoldAny parse_typed_value< String >(boost::property_tree::iptree &pt, const std::string &key)
Definition: objdict.cpp:157
static HoldAny func(boost::property_tree::iptree &pt, const std::string &key)
Definition: objdict.cpp:184
bool dynamic_channels_supported
Definition: objdict.h:109
std::string buffer2hex(const std::string &in, bool lc)
bool iterate(ObjectDictMap::const_iterator &it) const
Definition: objdict.cpp:77
bool simple_boot_up_slave
Definition: objdict.h:107
std::string formatValue(const T &value)
Definition: objdict.cpp:426
void set_access(ObjectDict::Entry &entry, std::string access)
Definition: objdict.cpp:83
std::shared_ptr< const Entry > EntryConstSharedPtr
Definition: objdict.h:189
std::unordered_set< uint16_t > dummy_usage
Definition: objdict.h:114
ObjectStorage(ObjectDictConstSharedPtr dict, uint8_t node_id, ReadFunc read_delegate, WriteFunc write_delegate)
Definition: objdict.cpp:383
HoldAny parse_int(boost::property_tree::iptree &pt, const std::string &key)
Definition: objdict.cpp:138
void read_integer(T &var, boost::property_tree::iptree &pt, const std::string &key)
Definition: objdict.cpp:192
uint32_t revision_number
Definition: objdict.h:103
uint8_t granularity
Definition: objdict.h:108
uint16_t nr_of_rx_pdo
Definition: objdict.h:111
ObjectDict::ObjectDictSharedPtr ObjectDictSharedPtr
Definition: objdict.h:235
WriteFunc write_delegate_
Definition: objdict.h:466
void init_nolock(const ObjectDict::Key &key, const ObjectDict::EntryConstSharedPtr &entry)
Definition: objdict.cpp:390
static std::function< void(const std::string &)> getWriter(ObjectStorage &storage, const ObjectDict::Key &key, bool cached)
Definition: objdict.cpp:470
static R * branch_type(const uint16_t data_type)
Definition: objdict.h:560
const size_t hash
Definition: objdict.h:125
uint16_t nr_of_tx_pdo
Definition: objdict.h:112
ReadFunc read_delegate_
Definition: objdict.h:465
ObjectStorageMap storage_
Definition: objdict.h:460
bool simple_boot_up_master
Definition: objdict.h:106
void parse_objects(ObjectDictSharedPtr dict, boost::property_tree::iptree &pt, const std::string &key)
Definition: objdict.cpp:264
bool set_cached(const T &val)
Definition: objdict.h:424
std::string vendor_name
Definition: objdict.h:99
std::size_t hash_value(ObjectDict::Key const &k)
Definition: objdict.cpp:9
static HoldAny read_value(boost::property_tree::iptree &pt, uint16_t data_type, const std::string &key)
Definition: objdict.cpp:164
size_t map(const ObjectDict::EntryConstSharedPtr &e, const ObjectDict::Key &key, const ReadFunc &read_delegate, const WriteFunc &write_delegate)
Definition: objdict.cpp:333
std::shared_ptr< ObjectDict > ObjectDictSharedPtr
Definition: objdict.h:217
static std::function< void(const std::string &)> func(ObjectStorage &storage, const ObjectDict::Key &key, bool cached)
Definition: objdict.cpp:465
TypeGuard type_guard
Definition: objdict.h:58
HoldAny parse_octets(boost::property_tree::iptree &pt, const std::string &key)
Definition: objdict.cpp:147
bool hex2buffer(std::string &out, const std::string &in_raw, bool pad)
void set(const T &val)
Definition: objdict.h:420
WriteStringFuncType getStringWriter(const ObjectDict::Key &key, bool cached=false)
Definition: objdict.cpp:476
ReadStringFuncType getStringReader(const ObjectDict::Key &key, bool cached=false)
Definition: objdict.cpp:449
#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
std::ostream & operator<<(std::ostream &stream, const NodeIdOffset< T > &n)
Definition: objdict.h:266
static size_t fromString(const std::string &str)
Definition: objdict.cpp:31
void parse_object(ObjectDictSharedPtr dict, boost::property_tree::iptree &pt, const std::string &name, const uint8_t *sub_index=0)
Definition: objdict.cpp:215
std::function< void(const std::string &)> WriteStringFuncType
Definition: objdict.h:526
std::string product_name
Definition: objdict.h:101
void read_var(ObjectDict::Entry &entry, boost::property_tree::iptree &object)
Definition: objdict.cpp:201
std::function< void(const ObjectDict::Entry &, String &)> ReadFunc
Definition: objdict.h:280
const String & data() const
Definition: objdict.h:79
HoldAny parse_typed_value(boost::property_tree::iptree &pt, const std::string &key)
Definition: objdict.cpp:153


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