CanOpenController.h
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 #ifndef CANOPENCONTROLLER_H
26 #define CANOPENCONTROLLER_H
27 
28 #include <boost/noncopyable.hpp>
29 #include <boost/shared_ptr.hpp>
31 
32 #include "helper.h"
33 #include "CanOpenReceiveThread.h"
34 #include "DS301Group.h"
35 #include "HeartBeatMonitor.h"
36 
37 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
38  // Schunk Diagnostics addon
39  #include <icl_comm_websocket/WsBroadcaster.h>
40 #else
41 // Forward Deklaration of the WsBroadcaster
42 // This is not needed for normal driver operation
43 // but might be added later. To keep the interface the same
44 // a forward declaration becomes necessary
45 namespace icl_comm{
46 namespace websocket{
47  class WsBroadcaster;
48 }}// NS end
49 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
50 
51 namespace icl_hardware{
52 namespace canopen_schunk{
53 
54 
65 class CanOpenController : protected virtual boost::noncopyable
66 {
67 public:
72 
82  CanOpenController(const std::string can_device_identifier = "/dev/pcanusb0",
83  const uint32_t baud_rate = 500,
84  const std::string& resource_folder_location = "");
85 
87 
94  void initNodes(const int16_t node_id = -1);
95 
101  void processCanMsgCallback (const icl_hardware::can::tCanMessage& msg);
102 
109  void reconnectCanDevice(const std::string& can_identifier, const uint32_t baud_rate);
110 
117  template <typename GroupT>
118  void addGroup(const std::string& identifier);
119 
131  template <typename GroupT>
132  boost::shared_ptr<GroupT> getGroup (const std::string& index = "default");
133 
139  void deleteGroup(const std::string& identifier);
140 
141 
149  template <typename NodeT>
150  void addNode(const uint8_t node_id, const std::string& group_name = "default");
151 
157  void deleteNode (const uint8_t node_id);
158 
165  CanDevPtr getCanDevice () const { return m_can_device; }
166 
170  void syncAll();
171 
179  template <typename NodeT>
180  boost::shared_ptr<NodeT> getNode (const uint8_t node_id);
181 
185  void stopAll();
186 
190  std::vector<uint8_t> getNodeList ();
191 
200  void enablePPMotion(const int16_t node_id = -1);
201 
202 private:
205  void init();
206 
208  void getResources();
209 
211  DS301Node::Ptr getNodeById (const uint8_t node_id);
212 
215 
218 
219 
221 
222  std::string m_can_device_name;
231 
234 
236  std::map<std::string, DS301Group::Ptr> m_groups;
238  std::map<uint8_t, DS301Node::Ptr> m_nodes;
239 
242 
247 
248 };
249 
250 
251 }// End of NS
252 }
253 
254 // include template implementations
255 #include "CanOpenController.hpp"
256 
257 #endif // CANOPENCONTROLLER_H
signed int int32_t
unsigned int uint32_t
std::string m_resource_folder_location
This folder contains for example the error code definitions.
CanDevPtr getCanDevice() const
Get a handle to the current CAN device. This is basically for debugging with a Dummy Can Device...
std::map< uint8_t, DS301Node::Ptr > m_nodes
Map of all nodes with id identifier.
uint32_t m_polling_period_ms
The CAN message polling period duration in milliseconds.
The CanOpenController class is the main entry point for any calls to the canOpen System.
std::map< std::string, DS301Group::Ptr > m_groups
Map of all node groups, with string identifier.
unsigned char uint8_t
boost::shared_ptr< const CanOpenController > ConstPtr
Shared pointer to a const CanOpenController.
boost::shared_ptr< CanOpenController > Ptr
Shared pointer to a CanOpenController.
signed short int16_t
CanOpenReceiveThreadPtr m_receive_thread
Handle for the can receive thread.
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.


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