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


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