CanOpenController.cpp
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 // This file is part of the SCHUNK Canopen Driver suite.
5 //
6 // This program is free software licensed under the LGPL
7 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
8 // You can find a copy of this license in LICENSE folder in the top
9 // directory of the source code.
10 //
11 // © Copyright 2016 SCHUNK GmbH, Lauffen/Neckar Germany
12 // © Copyright 2016 FZI Forschungszentrum Informatik, Karlsruhe, Germany
13 // -- END LICENSE BLOCK ------------------------------------------------
14 
15 //----------------------------------------------------------------------
23 //----------------------------------------------------------------------
24 
25 #include "CanOpenController.h"
27 #include "Logging.h"
28 #include "ds301.h"
29 #include "sync.h"
30 #include "exceptions.h"
31 
32 #include <cstdlib> // getenv
33 #include <dirent.h>
34 #include <boost/filesystem.hpp>
35 #include <boost/regex.hpp>
36 
37 namespace icl_hardware {
38 namespace canopen_schunk {
39 
40 CanOpenController::CanOpenController(const std::string can_device_identifier,
41  const uint32_t baud_rate,
42  const std::string& resource_folder_location
43  )
44  : m_can_device_name(can_device_identifier),
45  m_can_device_flags(O_RDWR|O_NONBLOCK),
46  m_can_device_acceptance_code(0xff),
47  m_can_device_acceptance_mask(0xff),
48  m_can_device_send_fifo_size(300),
49  m_can_device_receive_fifo_size(2000),
50  m_can_device_baud_rate(baud_rate),
51  m_heartbeat_monitor(new HeartBeatMonitor()),
52  m_polling_period_ms(1),
53  m_resource_folder_location(resource_folder_location),
54  m_ws_broadcast_counter(0),
55  m_ws_broadcast_rate(5)
56 {
57  init();
58 }
59 
61 {
62  // Stop receiving thread
63  if (m_receive_thread)
64  {
65  m_receive_thread->stop();
66  }
67 }
68 
70 {
71  for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin(); it != m_nodes.end(); ++it)
72  {
73  if (it->first == node_id || node_id < 0)
74  {
75  it->second->initNode();
76  }
77  }
78 }
79 
81 {
82  if (msg.id == ds301::ID_NMT)
83  {
84  LOGGING_DEBUG_C (CanOpen, CanOpenController, "NMT MESSAGE RECEIVED" << endl);
86  "Message id: " << msg.id << endl
87  << "Message length: " << msg.dlc << endl
88  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
89  }
90  else if (msg.id == ds301::ID_SYNC)
91  {
92  LOGGING_DEBUG_C (CanOpen, CanOpenController, "SYNC MESSAGE RECEIVED" << endl);
94  "Message id: " << msg.id << endl
95  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
96  }
97  else if (msg.id >= ds301::ID_EMCY_MIN && msg.id <= ds301::ID_EMCY_MAX)
98  {
99  LOGGING_DEBUG_C (CanOpen, CanOpenController, "EMCY MESSAGE RECEIVED" << endl);
101  "Message id: " << msg.id << endl
102  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
104  if (node)
105  {
106  try
107  {
108  node->m_emcy->update(msg);
109  }
110  catch (const std::exception& e)
111  {
112  LOGGING_ERROR (CanOpen, "Exception thrown in EMCY update function: " << e.what() << endl);
113  }
114  }
115  }
116  else if (msg.id == ds301::ID_TIME)
117  {
118  LOGGING_DEBUG_C (CanOpen, CanOpenController, "TIME MESSAGE RECEIVED" << endl);
120  "Message id: " << msg.id << endl
121  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
122  }
123  else if (msg.id >= ds301::ID_TPDO1_MIN && msg.id <= ds301::ID_TPDO1_MAX)
124  {
125  LOGGING_DEBUG_C (CanOpen, CanOpenController, "TPDO1 MESSAGE for node " << msg.id - ds301::ID_TPDO1_MIN+1 << " RECEIVED" << endl);
127  "Message id: " << msg.id << endl
128  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
130  if (node)
131  {
132  try
133  {
134  node->m_tpdos.at(0)->update(msg);
135  }
136  catch (const std::exception& e)
137  {
138  LOGGING_ERROR (CanOpen, "Exception thrown in PDO update function: " << e.what() << endl);
139  }
140  }
141  }
142  else if (msg.id >= ds301::ID_RPDO1_MIN && msg.id <= ds301::ID_RPDO1_MAX)
143  {
144  LOGGING_DEBUG_C (CanOpen, CanOpenController, "RPDO1 MESSAGE RECEIVED" << endl);
146  "Message id: " << msg.id << endl
147  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
148  }
149  else if (msg.id >= ds301::ID_TPDO2_MIN && msg.id <= ds301::ID_TPDO2_MAX)
150  {
151  LOGGING_DEBUG_C (CanOpen, CanOpenController, "TPDO2 MESSAGE RECEIVED" << endl);
153  "Message id: " << msg.id << endl
154  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
156  if (node)
157  {
158  try
159  {
160  node->m_tpdos.at(1)->update(msg);
161  }
162  catch (const std::exception& e)
163  {
164  LOGGING_ERROR (CanOpen, "Exception thrown in PDO update function: " << e.what() << endl);
165  }
166  }
167  }
168  else if (msg.id >= ds301::ID_RPDO2_MIN && msg.id <= ds301::ID_RPDO2_MAX)
169  {
170  LOGGING_DEBUG_C (CanOpen, CanOpenController, "RPDO2 MESSAGE RECEIVED" << endl);
172  "Message id: " << msg.id << endl
173  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
174  }
175  else if (msg.id >= ds301::ID_TPDO3_MIN && msg.id <= ds301::ID_TPDO3_MAX)
176  {
177  LOGGING_DEBUG_C (CanOpen, CanOpenController, "TPDO3 MESSAGE RECEIVED" << endl);
179  "Message id: " << msg.id << endl
180  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
182  if (node)
183  {
184  try
185  {
186  node->m_tpdos.at(2)->update(msg);
187  }
188  catch (const std::exception& e)
189  {
190  LOGGING_ERROR (CanOpen, "Exception thrown in PDO update function: " << e.what() << endl);
191  }
192  }
193  }
194  else if (msg.id >= ds301::ID_RPDO3_MIN && msg.id <= ds301::ID_RPDO3_MAX)
195  {
196  LOGGING_DEBUG_C (CanOpen, CanOpenController, "RPDO3 MESSAGE RECEIVED" << endl);
198  "Message id: " << msg.id << endl
199  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
200  }
201  else if (msg.id >= ds301::ID_TPDO4_MIN && msg.id <= ds301::ID_TPDO4_MAX)
202  {
203  LOGGING_DEBUG_C (CanOpen, CanOpenController, "TPDO4 MESSAGE RECEIVED" << endl);
205  "Message id: " << msg.id << endl
206  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
208  if (node)
209  {
210  try
211  {
212  node->m_tpdos.at(3)->update(msg);
213  }
214  catch (const std::exception& e)
215  {
216  LOGGING_ERROR (CanOpen, "Exception thrown in PDO update function: " << e.what() << endl);
217  }
218  }
219  }
220  else if (msg.id >= ds301::ID_RPDO4_MIN && msg.id <= ds301::ID_RPDO4_MAX)
221  {
222  LOGGING_DEBUG_C (CanOpen, CanOpenController, "RPDO4 MESSAGE RECEIVED" << endl);
224  "Message id: " << msg.id << endl
225  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
226  }
227  else if (msg.id >= ds301::ID_TSDO_MIN && msg.id <= ds301::ID_TSDO_MAX)
228  {
229  LOGGING_DEBUG_C (CanOpen, CanOpenController, "TSDO MESSAGE RECEIVED" << endl);
231  "Message id: " << msg.id << endl
232  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
234  if (node)
235  {
236  try
237  {
238  node->m_sdo.update(msg);
239  }
240  catch (const ResponseException& e)
241  {
242  LOGGING_ERROR (CanOpen, "Exception thrown in SDO update function: " << e.what() << endl);
243  }
244  }
245  }
246  else if (msg.id >= ds301::ID_RSDO_MIN && msg.id <= ds301::ID_RSDO_MAX)
247  {
248  LOGGING_DEBUG_C (CanOpen, CanOpenController, "RSDO MESSAGE RECEIVED" << endl);
250  "Message id: " << msg.id << endl
251  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
253  if (node)
254  {
255  try
256  {
257  node->m_sdo.update(msg);
258  }
259  catch (const ResponseException& e)
260  {
261  LOGGING_ERROR (CanOpen, "Exception thrown in SDO update function: " << e.what() << endl);
262  }
263  }
264  }
265  else if (msg.id >= ds301::ID_NMT_ERROR_MIN && msg.id <= ds301::ID_NMT_ERROR_MAX)
266  {
267  LOGGING_DEBUG_C (CanOpen, CanOpenController, "NMT_ERROR MESSAGE RECEIVED" << endl);
269  "Message id: " << msg.id << endl
270  << "Data: " << hexArrayToString(msg.data, msg.dlc) << endl);
271  uint8_t node_id = msg.id - ds301::ID_NMT_ERROR_MIN+1;
272  DS301Node::Ptr node = getNodeById(node_id);
273 
274  if (node)
275  {
276  try
277  {
278  node->m_nmt.update(msg);
279  }
280  catch (const ResponseException& e)
281  {
282  LOGGING_ERROR (CanOpen, "Exception thrown in NMT update function: " << e.what() << endl);
283  }
284  if (msg.data[0] != 0x0)
285  {
286  m_heartbeat_monitor->addHeartbeat(node_id);
287  }
288  }
289  else if ( msg.dlc == 1 && msg.data[0] == 0x0)
290  {
291  // TODO (optional): If byte 0: add new node (autodiscovery)
292  LOGGING_INFO_C (CanOpen, CanOpenController, "NMT bootup of node " << msg.id - ds301::ID_NMT_ERROR_MIN+1 << endl);
293  }
294  }
295 }
296 
297 void CanOpenController::reconnectCanDevice(const std::string& can_identifier, const uint32_t baud_rate)
298 {
299  if (baud_rate != 0)
300  {
301  m_can_device_baud_rate = baud_rate;
302  }
303  m_can_device_name = can_identifier;
304 
305  if (m_receive_thread)
306  {
307  m_receive_thread->stop();
308  }
309 
310  try
311  {
312  init();
313  }
314  catch (const DeviceException& e)
315  {
316  LOGGING_ERROR_C (CanOpen, CanOpenController, "Initializing device failed. Reason: " << e.what());
317  }
318 }
319 
321 {
322  #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
323  m_ws_broadcaster = boost::shared_ptr<icl_comm::websocket::WsBroadcaster>(new icl_comm::websocket::WsBroadcaster(icl_comm::websocket::WsBroadcaster::eRT_LWA4P));
324  #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
325 
326 
327  getResources();
328 
329  if (m_can_device_name == "Dummy")
330  {
338  ));
339  }
340  else if (m_can_device_name == "auto")
341  {
342  std::vector<std::string> names;
343  boost::regex pattern("pcan(usb|pci)\\d+");
344 
345  DIR* dir;
346  struct dirent* ent;
347  if ((dir = opendir("/dev")) != NULL)
348  {
349  /* print all the files and directories within directory */
350  while ((ent = readdir(dir)) != NULL)
351  {
352  std::string s = ent->d_name;
353  if (boost::regex_match(s, pattern))
354  {
355  names.push_back("/dev/" + s);
356  LOGGING_INFO(CanOpen, "Found " << s << endl);
357  }
358  }
359  closedir(dir);
360  }
361 
362  bool can_found = false;
363  LOGGING_INFO (CanOpen, "CAN Device was set to auto. " << endl);
364 
365  for (size_t num = 0; num < names.size() ; ++num)
366  {
367  m_can_device_name = names[num];
368  LOGGING_INFO(CanOpen, "Trying CAN device: " << m_can_device_name << "... " << endl);
369  try
370  {
378  ));
379 
380  if (m_can_device)
381  {
382  if (!m_can_device->IsInitialized())
383  {
384  std::stringstream ss;
385  continue;
386  }
387  }
388  can_found = true;
389 
390  break;
391 
392  }
393  catch (DeviceException const& e)
394  {
395  LOGGING_INFO(CanOpen, e.what() << endl);
396  can_found = false;
397  }
398  }
399  if (!can_found)
400  {
401  LOGGING_ERROR(CanOpen, " CAN DEVICE COULD NOT BE OPENED. \n >> Giving up.");
402  exit(-123);
403  return;
404  }
405  }
406  else
407  {
415  ));
416  }
417 
418  if (m_can_device)
419  {
420  if (!m_can_device->IsInitialized())
421  {
422  std::stringstream ss;
423  ss << "FATAL: COULD NOT INITIALIZE CAN DEVICE in " << m_can_device_name;
424 
425  throw DeviceException(ss.str());
426  }
427  }
428  else
429  {
430  std::stringstream ss;
431  ss << "FATAL: COULD NOT GET VALID CAN DEVICE in " << m_can_device_name;
432 
433  throw DeviceException(ss.str());
434  }
435 
437  m_can_device,
438  boost::bind(&CanOpenController::processCanMsgCallback, this, _1)
439  ));
440 
441  if (!m_receive_thread)
442  {
443  throw DeviceException("FATAL: Could not start listener thread for CAN bus.");
444  }
445 
446  // add default DS402Group
447  addGroup<DS402Group>("default");
448  m_heartbeat_monitor->registerErrorCallback(boost::bind(&CanOpenController::stopAll, this));
449 }
450 
451 void CanOpenController::deleteGroup(const std::string& identifier)
452 {
453  std::string sanitized_identifier = sanitizeString(identifier);
454 
455  std::map<std::string, DS301Group::Ptr>::iterator group_it;
456  group_it = m_groups.find(sanitized_identifier);
457  if (group_it != m_groups.end())
458  {
459  std::vector<uint8_t> deleted_node_ids;
460  group_it->second->deleteNodes(deleted_node_ids); // This will return the IDs of deleted nodes
461 
462  // Now also delete shared pointers in controller
463  for (std::vector<uint8_t>::iterator it = deleted_node_ids.begin();
464  it != deleted_node_ids.end();
465  ++it)
466  {
467  // Find the node with given Id
468  std::map<uint8_t, DS301Node::Ptr>::iterator node_it = m_nodes.find(*it);
469  assert(node_it->second.use_count() == 1);
470  m_nodes.erase(node_it);
471  }
472 
473  m_groups.erase(group_it);
474  }
475  else
476  {
477  LOGGING_ERROR_C(CanOpen, CanOpenController, "No group with the given identifer " << sanitized_identifier
478  << " exists. Not deleting anything." << endl);
479  }
480 }
481 
483 {
484  // Delete node in group
485  for (std::map<std::string, DS301Group::Ptr>::iterator it = m_groups.begin();
486  it != m_groups.end();
487  ++it)
488  {
489  if (it->second->deleteNodeFromId(node_id))
490  {
491  // group for node_id was found and node was deleted.
492  break;
493  }
494  }
495 
496  // Delete node in controller's list
497  std::map<uint8_t, DS301Node::Ptr>::iterator node_it = m_nodes.find(node_id);
498  assert(node_it->second.use_count() == 1);
499  m_nodes.erase(node_it);
500 }
501 
503 {
504  std::map<uint8_t, DS301Node::Ptr>::iterator node_it = m_nodes.find(node_id);
505  if (node_it == m_nodes.end())
506  {
507  LOGGING_ERROR_C(CanOpen, CanOpenController, "A node with the given ID " << node_id <<
508  " does not exist. Therefore this CAN message will be ignored." << endl);
509  // Return a NULL pointer
510  return DS301Node::Ptr();
511  }
512  return node_it->second;
513 }
514 
516 {
517  boost::filesystem::path resources_path(m_resource_folder_location);
518 
519  if (m_resource_folder_location == "")
520  {
521  char const* tmp = std::getenv("CANOPEN_RESOURCE_PATH");
522  if (tmp == NULL)
523  {
525  CanOpen,
527  "The environment variable 'CANOPEN_RESOURCE_PATH' could not be read. Using relative path 'resources/'" << endl);
528  resources_path = boost::filesystem::path("resources");
529  }
530  else
531  {
532  resources_path = boost::filesystem::path(tmp);
533  }
534  }
535 
536  std::string sdo_errors_filename = (resources_path / boost::filesystem::path("SDO.ini")).string();
537  SDO::addErrorMapFromFile( sdo_errors_filename );
538 
539  std::string emcy_emergency_errors_filename = (resources_path / boost::filesystem::path("EMCY.ini")).string();
540  EMCY::addEmergencyErrorMap( emcy_emergency_errors_filename, "emergency_errors");
541  EMCY::addErrorRegisterMap( emcy_emergency_errors_filename, "error_registers");
542 
543  emcy_emergency_errors_filename = (resources_path / boost::filesystem::path("EMCY_DS402.ini")).string();
544  EMCY::addEmergencyErrorMap( emcy_emergency_errors_filename, "emergency_errors");
545 }
546 
548 {
549  for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin();
550  it != m_nodes.end();
551  ++it)
552  {
553  it->second->downloadPDOs();
554  }
555 
557 
558  for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin();
559  it != m_nodes.end();
560  ++it)
561  {
562  it->second->uploadPDOs();
563  }
564 
565  #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
567  {
568  if (!m_ws_broadcaster->sendState())
569  {
570  // LOGGING_WARNING_C(
571  // CanOpen,
572  // CanOpenController, "Can't send ws_broadcaster state - reconnect pending..." << endl);
573  }
575  }
577  #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
578 
579 }
580 
582 {
583  LOGGING_INFO (CanOpen, "Stop of all nodes requested!" << endl);
584  for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin();
585  it != m_nodes.end();
586  ++it)
587  {
588  it->second->stopNode();
589  }
590 }
591 
592 std::vector< uint8_t > CanOpenController::getNodeList()
593 {
594  std::vector <uint8_t> node_list;
595 
596  size_t i=0;
597  for (std::map<uint8_t, DS301Node::Ptr>::iterator it = m_nodes.begin();
598  it != m_nodes.end();
599  ++it)
600  {
601  it->second->downloadPDOs();
602  node_list.push_back(it->second->getNodeId());
603  ++i;
604  }
605 
606  return node_list;
607 }
608 
609 
610 
612 {
613  syncAll();
614  usleep(5000); // sleep 5 ms
615 
616  LOGGING_TRACE_C (CanOpen, CanOpenController, "in function " << __FUNCTION__ << endl);
617 
618  for (std::map<std::string, DS301Group::Ptr>::iterator it = m_groups.begin();
619  it != m_groups.end();
620  ++it)
621  {
622  DS402Group::Ptr group_ds402 = boost::dynamic_pointer_cast<DS402Group>(it->second);
623  if (group_ds402)
624  {
625  group_ds402->startPPMovement(node_id);
626  }
627  }
628 
629  syncAll();
630  usleep(5000); // sleep 5 ms
631 
632  for (std::map<std::string, DS301Group::Ptr>::iterator it = m_groups.begin();
633  it != m_groups.end();
634  ++it)
635  {
636  DS402Group::Ptr group_ds402 = boost::dynamic_pointer_cast<DS402Group>(it->second);
637  if (group_ds402)
638  {
639  group_ds402->acceptPPTargets(node_id);
640  }
641  }
642  syncAll();
643  usleep(5000); // sleep 5 ms
644 
645 }
646 
647 }}//end of NS
static const uint16_t ID_RSDO_MAX
Definition: ds301.h:79
unsigned int uint32_t
static TimeSpan createFromMSec(int64_t msec)
static const uint16_t ID_TSDO_MAX
Definition: ds301.h:77
#define LOGGING_INFO_C(streamname, classname, arg)
static const uint16_t ID_RPDO1_MIN
Definition: ds301.h:54
static const uint16_t ID_RSDO_MIN
Definition: ds301.h:78
static const uint16_t ID_TPDO3_MIN
Definition: ds301.h:64
virtual const char * what() const _GLIBCXX_USE_NOEXCEPT
Definition: exceptions.h:79
static void addEmergencyErrorMap(const std::string &filename, const std::string &block_identifier)
Adds new information from an ini file to the emergency error map.
Definition: EMCY.cpp:213
boost::shared_ptr< DS301Node > Ptr
Shared pointer to a DS301Node.
Definition: DS301Node.h:95
std::string m_resource_folder_location
This folder contains for example the error code definitions.
std::string hexArrayToString(const unsigned char *msg, const uint8_t length)
Transforms an array of unsigned chars into a string of Hex representations of those chars...
Definition: helper.cpp:42
#define LOGGING_INFO(streamname, arg)
void initNodes(const int16_t node_id=-1)
Initializes a node with a given ID or all nodes.
void deleteNode(const uint8_t node_id)
Delete a node with a given CANOPEN-ID.
XmlRpcServer s
void getResources()
Load resources like error-code lookup maps.
static const uint16_t ID_TPDO2_MAX
Definition: ds301.h:59
std::vector< uint8_t > getNodeList()
Returns a list containing all used node ids.
virtual const char * what() const _GLIBCXX_USE_NOEXCEPT
Definition: exceptions.h:144
static tCanDevice * Create(const char *device_name, int flags, unsigned char acceptance_code, unsigned char acceptance_mask, unsigned int baud_rate, unsigned send_fifo_size, unsigned receive_fifo_size)
std::map< uint8_t, DS301Node::Ptr > m_nodes
Map of all nodes with id identifier.
The DS402Group class is the base class for canOpen devices implementing the DS402 device protocol (mo...
Definition: DS402Group.h:45
static const uint16_t ID_TIME
Definition: ds301.h:49
uint32_t m_polling_period_ms
The CAN message polling period duration in milliseconds.
static const uint16_t ID_NMT_ERROR_MAX
Definition: ds301.h:82
#define LOGGING_WARNING_C(streamname, classname, arg)
static void sendSync(const CanDevPtr &can_device)
sendSync sends a SYNC message which is used to ensure synchronous processing of all CanOpen nodes...
Definition: sync.h:41
#define LOGGING_ERROR(streamname, arg)
static const uint16_t ID_NMT_ERROR_MIN
Definition: ds301.h:81
The CanOpenController class is the main entry point for any calls to the canOpen System.
void processCanMsgCallback(const icl_hardware::can::tCanMessage &msg)
Incoming can messages are processed in this function and forwarded to the addressed node...
void enablePPMotion(const int16_t node_id=-1)
When using the ProfilePositionMode is used, in addition to setting the target motion has to be trigge...
std::map< std::string, DS301Group::Ptr > m_groups
Map of all node groups, with string identifier.
static const uint16_t ID_EMCY_MIN
Definition: ds301.h:47
static const uint16_t ID_EMCY_MAX
Definition: ds301.h:48
static const uint16_t ID_RPDO2_MIN
Definition: ds301.h:60
unsigned char uint8_t
#define LOGGING_DEBUG_C(streamname, classname, arg)
Exceptions relating to device responses.
Definition: exceptions.h:68
static const uint16_t ID_NMT
Definition: ds301.h:45
static const uint16_t ID_RPDO2_MAX
Definition: ds301.h:61
ThreadStream & endl(ThreadStream &stream)
static const uint16_t ID_TPDO4_MIN
Definition: ds301.h:70
The CanOpenReceiveThread class handles incoming canOpen messages.
If something goes wrong with the host&#39;s CAN controller, this exception will be used.
Definition: exceptions.h:135
static const uint16_t ID_RPDO1_MAX
Definition: ds301.h:55
static const uint16_t ID_SYNC
Definition: ds301.h:46
void deleteGroup(const std::string &identifier)
Deletes a group with the given identifier. Also deletes all its nodes.
static const uint16_t ID_RPDO3_MAX
Definition: ds301.h:67
static const uint16_t ID_TPDO1_MAX
Definition: ds301.h:53
signed short int16_t
CanOpenReceiveThreadPtr m_receive_thread
Handle for the can receive thread.
static void addErrorMapFromFile(const std::string &filename)
Adds an error map from an INI file to all SDOs. This should be called once to get human readable erro...
Definition: SDO.cpp:339
static const uint16_t ID_TPDO3_MAX
Definition: ds301.h:65
boost::shared_ptr< icl_comm::websocket::WsBroadcaster > m_ws_broadcaster
Interface to send out diagnostics data. Only available if compiled with IC_BUILDER_ICL_COMM_WEBSOCKET...
CanDevPtr m_can_device
Handle for the can device.
std::string sanitizeString(const std::string &text)
This function removes all non-graphical characters from the given string.
Definition: helper.cpp:62
void stopAll()
Calls stop() on all registered nodes.
static const uint16_t ID_TSDO_MIN
Definition: ds301.h:76
static const uint16_t ID_TPDO4_MAX
Definition: ds301.h:71
static const uint16_t ID_RPDO4_MIN
Definition: ds301.h:72
static void addErrorRegisterMap(const std::string &filename, const std::string &block_identifier)
Adds new information from an ini file to the error_register map.
Definition: EMCY.cpp:225
#define LOGGING_TRACE_C(streamname, classname, arg)
static const uint16_t ID_TPDO2_MIN
Definition: ds301.h:58
void reconnectCanDevice(const std::string &can_identifier, const uint32_t baud_rate)
Reconnects the CAN device with the given configuration.
CanOpenController(const std::string can_device_identifier="/dev/pcanusb0", const uint32_t baud_rate=500, const std::string &resource_folder_location="")
CanOpenController constructor.
DS301Node::Ptr getNodeById(const uint8_t node_id)
get a handle for a node identified by its CANOPEN-ID
static const uint16_t ID_RPDO4_MAX
Definition: ds301.h:73
#define LOGGING_ERROR_C(streamname, classname, arg)
void syncAll()
Downloads all the RPDOs, Sends a Sync and Uploads all the TPDOs.
static const uint16_t ID_RPDO3_MIN
Definition: ds301.h:66
int usleep(unsigned long useconds)
static const uint16_t ID_TPDO1_MIN
Definition: ds301.h:52


schunk_canopen_driver
Author(s): Felix Mauch , Georg Heppner
autogenerated on Mon Jun 10 2019 15:07:49