pdo.cpp
Go to the documentation of this file.
2 
3 using namespace canopen;
4 
5 #pragma pack(push) /* push current alignment to stack */
6 #pragma pack(1) /* set alignment to 1 byte boundary */
7 
8 class PDOid{
9  const uint32_t value_;
10 public:
11  static const unsigned int ID_MASK = (1u << 29)-1;
12  static const unsigned int EXTENDED_MASK = (1u << 29);
13  static const unsigned int NO_RTR_MASK = (1u << 30);
14  static const unsigned int INVALID_MASK = (1u << 31);
15 
16  PDOid(const uint32_t &val)
17  : value_(val)
18  {}
19  can::Header header(bool fill_rtr = false) const {
20  return can::Header(value_ & ID_MASK, value_ & EXTENDED_MASK, fill_rtr && !(value_ & NO_RTR_MASK), false);
21  }
22  bool isInvalid() const { return value_ & INVALID_MASK; }
23 };
24 
25 struct PDOmap{
26  uint8_t length;
27  uint8_t sub_index;
28  uint16_t index;
29  PDOmap(uint32_t val)
30  : length(val & 0xFF),
31  sub_index((val>>8) & 0xFF),
32  index(val>>16)
33  {}
34 };
35 
36 #pragma pack(pop) /* pop previous alignment from stack */
37 
38 
39 const uint8_t SUB_COM_NUM = 0;
40 const uint8_t SUB_COM_COB_ID = 1;
41 const uint8_t SUB_COM_TRANSMISSION_TYPE = 2;
42 const uint8_t SUB_COM_RESERVED = 4;
43 
44 const uint8_t SUB_MAP_NUM = 0;
45 
46 const uint16_t RPDO_COM_BASE =0x1400;
47 const uint16_t RPDO_MAP_BASE =0x1600;
48 const uint16_t TPDO_COM_BASE =0x1800;
49 const uint16_t TPDO_MAP_BASE =0x1A00;
50 
51 bool check_com_changed(const ObjectDict &dict, const uint16_t com_id){
52  bool com_changed = false;
53 
54  // check if com parameter has to be set
55  for(uint8_t sub = 0; sub <=6 ; ++sub){
56  try{
57  if(!dict(com_id,sub).init_val.is_empty()){
58  com_changed = true;
59  break;
60  }
61  }
62  catch (std::out_of_range) {}
63  }
64  return com_changed;
65 }
66 
67 bool check_map_changed(const uint8_t &num, const ObjectDict &dict, const uint16_t &map_index){
68  bool map_changed = false;
69 
70  // check if mapping has to be set
71  if(num <= 0x40){
72  for(uint8_t sub = 1; sub <=num ; ++sub){
73  try{
74  if(!dict(map_index,sub).init_val.is_empty()){
75  map_changed = true;
76  break;
77  }
78  }
79  catch (std::out_of_range) {}
80  }
81  }else{
82  map_changed = dict( map_index ,0 ).init_val.is_empty();
83  }
84  return map_changed;
85 }
86 void PDOMapper::PDO::parse_and_set_mapping(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index, const bool &read, const bool &write){
87 
88  const canopen::ObjectDict & dict = *storage->dict_;
89 
91  storage->entry(num_entry, map_index, SUB_MAP_NUM);
92 
93  uint8_t map_num;
94 
95  try{
96  map_num = num_entry.desc().value().get<uint8_t>();
97  }catch(...){
98  map_num = 0;
99  }
100 
101  bool map_changed = check_map_changed(map_num, dict, map_index);
102 
103  // disable PDO if needed
105  storage->entry(cob_id, com_index, SUB_COM_COB_ID);
106 
107  bool com_changed = check_com_changed(dict, map_index);
108  if((map_changed || com_changed) && cob_id.desc().writable){
109  cob_id.set(cob_id.get() | PDOid::INVALID_MASK);
110  }
111  if(map_num > 0 && map_num <= 0x40){ // actual mapping
112  if(map_changed){
113  num_entry.set(0);
114  }
115 
116  frame.dlc = 0;
117  for(uint8_t sub = 1; sub <=map_num; ++sub){
119  storage->entry(mapentry, map_index, sub);
120  const HoldAny init = dict(map_index ,sub).init_val;
121  if(!init.is_empty()) mapentry.set(init.get<uint32_t>());
122 
123  PDOmap param(mapentry.get_cached());
124  BufferSharedPtr b = std::make_shared<Buffer>(param.length/8);
125  if(param.index < 0x1000){
126  // TODO: check DummyUsage
127  }else{
130 
131  if(read){
132  rd = std::bind<void(Buffer::*)(const canopen::ObjectDict::Entry&, String&)>(&Buffer::read, b.get(), std::placeholders::_1, std::placeholders::_2);
133  }
134  if(read || write)
135  {
136  wd = std::bind<void(Buffer::*)(const canopen::ObjectDict::Entry&, const String&)>(&Buffer::write, b.get(), std::placeholders::_1, std::placeholders::_2);
137  size_t l = storage->map(param.index, param.sub_index, rd, wd);
138  assert(l == param.length/8);
139  }
140  }
141 
142  frame.dlc += b->size;
143  assert( frame.dlc <= 8 );
144  b->clean();
145  buffers.push_back(b);
146  }
147  }
148  if(com_changed){
149  uint8_t subs = dict(com_index, SUB_COM_NUM).value().get<uint8_t>();
150  for(uint8_t i = SUB_COM_NUM+1; i <= subs; ++i){
151  if(i == SUB_COM_COB_ID || i == SUB_COM_RESERVED) continue;
152  try{
153  storage->init(ObjectDict::Key(com_index, i));
154  }
155  catch (const std::out_of_range &){
156  // entry was not provided, so skip it
157  }
158  }
159  }
160  if(map_changed){
161  num_entry.set(map_num);
162  }
163  if((com_changed || map_changed) && cob_id.desc().writable){
164  storage->init(ObjectDict::Key(com_index, SUB_COM_COB_ID));
165 
166  cob_id.set(NodeIdOffset<uint32_t>::apply(dict(com_index, SUB_COM_COB_ID).value(), storage->node_id_));
167  }
168 
169 
170 }
172 :interface_(interface)
173 {
174 }
176  boost::mutex::scoped_lock lock(mutex_);
177 
178  try{
179  rpdos_.clear();
180 
181  const canopen::ObjectDict & dict = *storage->dict_;
182  for(uint16_t i=0; i < 512 && rpdos_.size() < dict.device_info.nr_of_tx_pdo;++i){ // TPDOs of device
183  if(!dict.has(TPDO_COM_BASE + i,0) && !dict.has(TPDO_MAP_BASE + i,0)) continue;
184 
186  if(rpdo){
187  rpdos_.insert(rpdo);
188  }
189  }
190  // ROSCANOPEN_DEBUG("canopen_master", "RPDOs: " << rpdos_.size());
191 
192  tpdos_.clear();
193  for(uint16_t i=0; i < 512 && tpdos_.size() < dict.device_info.nr_of_rx_pdo;++i){ // RPDOs of device
194  if(!dict.has(RPDO_COM_BASE + i,0) && !dict.has(RPDO_MAP_BASE + i,0)) continue;
195 
197  if(tpdo){
198  tpdos_.insert(tpdo);
199  }
200  }
201  // ROSCANOPEN_DEBUG("canopen_master", "TPDOs: " << tpdos_.size());
202 
203  return true;
204  }
205  catch(const std::out_of_range &e){
206  status.error(std::string("PDO error: ") + e.what());
207  return false;
208  }
209 }
210 
211 
212 bool PDOMapper::RPDO::init(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index){
213  boost::mutex::scoped_lock lock(mutex);
214  listener_.reset();
215  const canopen::ObjectDict & dict = *storage->dict_;
216  parse_and_set_mapping(storage, com_index, map_index, true, false);
217 
218  PDOid pdoid( NodeIdOffset<uint32_t>::apply(dict(com_index, SUB_COM_COB_ID).value(), storage->node_id_) );
219 
220  if(buffers.empty() || pdoid.isInvalid()){
221  return false;
222  }
223 
224  frame = pdoid.header(true);
225 
226  transmission_type = dict(com_index, SUB_COM_TRANSMISSION_TYPE).value().get<uint8_t>();
227 
228  listener_ = interface_->createMsgListenerM(pdoid.header(), this, &RPDO::handleFrame);
229 
230  return true;
231 }
232 
233 bool PDOMapper::TPDO::init(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index){
234  boost::mutex::scoped_lock lock(mutex);
235  const canopen::ObjectDict & dict = *storage->dict_;
236 
237 
238  PDOid pdoid( NodeIdOffset<uint32_t>::apply(dict(com_index, SUB_COM_COB_ID).value(), storage->node_id_) );
239  frame = pdoid.header();
240 
241  parse_and_set_mapping(storage, com_index, map_index, false, true);
242  if(buffers.empty() || pdoid.isInvalid()){
243  return false;
244  }
246  storage->entry(tt, com_index, SUB_COM_TRANSMISSION_TYPE);
247  transmission_type = tt.desc().value().get<uint8_t>();
248 
249  if(transmission_type != 1 && transmission_type <=240){
250  tt.set(1); // enforce 1 for compatibility
251  }
252  return true;
253 }
254 
256  boost::mutex::scoped_lock lock(mutex);
257 
258  bool updated = false;
259  size_t len = frame.dlc;
260  can::Frame::value_type * dest = frame.c_array();
261  for(std::vector< BufferSharedPtr >::iterator b_it = buffers.begin(); b_it != buffers.end(); ++b_it){
262  Buffer &b = **b_it;
263  if(len >= b.size){
264  updated = b.read(dest, len) || updated;
265  len -= b.size;
266  dest += b.size;
267  }else{
268  // ERROR
269  }
270  }
271 
272  if( len != 0){
273  // ERROR
274  }
275  if(updated){
276  interface_->send( frame );
277  }else{
278  // TODO: Notify
279  }
280 }
281 
283  boost::mutex::scoped_lock lock(mutex);
284  if((transmission_type >= 1 && transmission_type <= 240) || transmission_type == 0xFC){ // cyclic
285  if(timeout > 0){
286  --timeout;
287  }else if(timeout == 0) {
288  status.warn("RPDO timeout");
289  }
290  }
291  if(transmission_type == 0xFC || transmission_type == 0xFD){
292  if(frame.is_rtr){
293  interface_->send(frame);
294  }
295  }
296 }
297 
299  size_t offset = 0;
300  const uint8_t * src = msg.data.data();
301  for(std::vector<BufferSharedPtr >::iterator it = buffers.begin(); it != buffers.end(); ++it){
302  Buffer &b = **it;
303 
304  if( offset + b.size <= msg.dlc ){
305  b.write(src+offset, b.size);
306  offset += b.size;
307  }else{
308  // ERROR
309  }
310  }
311  if( offset != msg.dlc ){
312  // ERROR
313  }
314  {
315  boost::mutex::scoped_lock lock(mutex);
316  if(transmission_type >= 1 && transmission_type <= 240){
317  timeout = transmission_type + 2;
318  }else if(transmission_type == 0xFC || transmission_type == 0xFD){
319  if(frame.is_rtr){
320  timeout = 1+2;
321  }
322  }
323  }
324 }
325 
327  boost::mutex::scoped_lock lock(mutex_);
328  for(std::unordered_set<RPDO::RPDOSharedPtr >::iterator it = rpdos_.begin(); it != rpdos_.end(); ++it){
329  (*it)->sync(status);
330  }
331 }
333  boost::mutex::scoped_lock lock(mutex_);
334  for(std::unordered_set<TPDO::TPDOSharedPtr >::iterator it = tpdos_.begin(); it != tpdos_.end(); ++it){
335  (*it)->sync();
336  }
337  return true; // TODO: check for errors
338 }
339 
340 bool PDOMapper::Buffer::read(uint8_t* b, const size_t len){
341  boost::mutex::scoped_lock lock(mutex);
342  if(size > len){
343  BOOST_THROW_EXCEPTION( std::bad_cast() );
344  }
345  if(empty) return false;
346 
347  memcpy(b,&buffer[0], size);
348  bool was_dirty = dirty;
349  dirty = false;
350  return was_dirty;
351 }
352 void PDOMapper::Buffer::write(const uint8_t* b, const size_t len){
353  boost::mutex::scoped_lock lock(mutex);
354  if(size > len){
355  BOOST_THROW_EXCEPTION( std::bad_cast() );
356  }
357  empty = false;
358  dirty = true;
359  memcpy(&buffer[0], b, size);
360 }
362  boost::mutex::scoped_lock lock(mutex);
363  time_point abs_time = get_abs_time(boost::chrono::seconds(1));
364  if(size != data.size()){
365  THROW_WITH_KEY(std::bad_cast(), ObjectDict::Key(entry));
366  }
367  if(empty){
368  THROW_WITH_KEY(TimeoutException("PDO data empty"), ObjectDict::Key(entry));
369  }
370  if(dirty){
371  data.assign(buffer.begin(), buffer.end());
372  dirty = false;
373  }
374 }
376  boost::mutex::scoped_lock lock(mutex);
377  if(size != data.size()){
378  THROW_WITH_KEY(std::bad_cast(), ObjectDict::Key(entry));
379  }
380  empty = false;
381  dirty = true;
382  buffer.assign(data.begin(),data.end());
383 }
static RPDOSharedPtr create(const can::CommInterfaceSharedPtr interface, const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index)
Definition: canopen.h:119
std::array< value_type, 8 > data
bool init(const ObjectStorageSharedPtr storage, LayerStatus &status)
Definition: pdo.cpp:175
bool check_map_changed(const uint8_t &num, const ObjectDict &dict, const uint16_t &map_index)
Definition: pdo.cpp:67
bool read(uint8_t *b, const size_t len)
Definition: pdo.cpp:340
bool check_com_changed(const ObjectDict &dict, const uint16_t com_id)
Definition: pdo.cpp:51
bool write()
Definition: pdo.cpp:332
std::unordered_set< TPDO::TPDOSharedPtr > tpdos_
Definition: canopen.h:137
const uint16_t RPDO_COM_BASE
Definition: pdo.cpp:46
unsigned char value_type
std::shared_ptr< TPDO > TPDOSharedPtr
Definition: canopen.h:101
const uint8_t SUB_COM_NUM
Definition: pdo.cpp:39
PDOid(const uint32_t &val)
Definition: pdo.cpp:16
const void warn(const std::string &r)
Definition: layer.h:44
uint8_t sub_index
Definition: pdo.cpp:27
const T & get() const
Definition: objdict.h:86
std::shared_ptr< RPDO > RPDOSharedPtr
Definition: canopen.h:118
const EntryConstSharedPtr & get(const Key &k) const
Definition: objdict.h:197
const uint8_t SUB_MAP_NUM
Definition: pdo.cpp:44
const uint16_t TPDO_MAP_BASE
Definition: pdo.cpp:49
Definition: pdo.cpp:25
PDOmap(uint32_t val)
Definition: pdo.cpp:29
std::unordered_set< RPDO::RPDOSharedPtr > rpdos_
Definition: canopen.h:136
const HoldAny & value() const
Definition: objdict.h:186
const uint16_t RPDO_MAP_BASE
Definition: pdo.cpp:47
const uint32_t value_
Definition: pdo.cpp:9
PDOMapper(const can::CommInterfaceSharedPtr interface)
Definition: pdo.cpp:171
boost::chrono::high_resolution_clock::time_point time_point
Definition: canopen.h:18
uint16_t index
Definition: pdo.cpp:28
std::shared_ptr< CommInterface > CommInterfaceSharedPtr
std::shared_ptr< Buffer > BufferSharedPtr
Definition: canopen.h:90
void read(LayerStatus &status)
Definition: pdo.cpp:326
bool is_empty() const
Definition: objdict.h:77
uint16_t nr_of_rx_pdo
Definition: objdict.h:111
void sync(LayerStatus &status)
Definition: pdo.cpp:282
void write(const uint8_t *b, const size_t len)
Definition: pdo.cpp:352
bool init(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index)
Definition: pdo.cpp:212
static const unsigned int INVALID_MASK
Definition: pdo.cpp:14
can::Header header(bool fill_rtr=false) const
Definition: pdo.cpp:19
const uint8_t SUB_COM_TRANSMISSION_TYPE
Definition: pdo.cpp:41
uint16_t nr_of_tx_pdo
Definition: objdict.h:112
bool has(uint16_t i, uint8_t s) const
Definition: objdict.h:200
Definition: pdo.cpp:8
const can::CommInterfaceSharedPtr interface_
Definition: canopen.h:139
const ObjectDict::Entry & desc() const
Definition: objdict.h:451
static TPDOSharedPtr create(const can::CommInterfaceSharedPtr interface, const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index)
Definition: canopen.h:103
const uint16_t TPDO_COM_BASE
Definition: pdo.cpp:48
const DeviceInfo device_info
Definition: objdict.h:219
boost::mutex mutex_
Definition: canopen.h:72
const void error(const std::string &r)
Definition: layer.h:45
uint8_t length
Definition: pdo.cpp:26
void set(const T &val)
Definition: objdict.h:420
bool init(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index)
Definition: pdo.cpp:233
unsigned char dlc
bool isInvalid() const
Definition: pdo.cpp:22
ObjectDictMap dict_
Definition: objdict.h:233
#define THROW_WITH_KEY(e, k)
Definition: objdict.h:117
time_point get_abs_time(const time_duration &timeout)
Definition: canopen.h:20
void parse_and_set_mapping(const ObjectStorageSharedPtr &storage, const uint16_t &com_index, const uint16_t &map_index, const bool &read, const bool &write)
Definition: pdo.cpp:86
std::function< void(const ObjectDict::Entry &, const String &)> WriteFunc
Definition: objdict.h:283
ObjectStorage::ObjectStorageSharedPtr ObjectStorageSharedPtr
Definition: objdict.h:537
const uint8_t SUB_COM_RESERVED
Definition: pdo.cpp:42
std::function< void(const ObjectDict::Entry &, String &)> ReadFunc
Definition: objdict.h:280
void handleFrame(const can::Frame &msg)
Definition: pdo.cpp:298
const uint8_t SUB_COM_COB_ID
Definition: pdo.cpp:40


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