can_layer.h
Go to the documentation of this file.
1 #ifndef H_CAN_LAYER
2 #define H_CAN_LAYER
3 
5 #include "layer.h"
6 
7 namespace canopen{
8 
9 class CANLayer: public Layer{
10  boost::mutex mutex_;
12  const std::string device_;
13  const bool loopback_;
16  void handleFrame(const can::Frame & msg){
17  boost::mutex::scoped_lock lock(mutex_);
18  last_error_ = msg;
19  LOG("ID: " << msg.id);
20  }
21  boost::shared_ptr<boost::thread> thread_;
22 
23 public:
24  CANLayer(const can::DriverInterfaceSharedPtr &driver, const std::string &device, bool loopback)
25  : Layer(device + " Layer"), driver_(driver), device_(device), loopback_(loopback) { assert(driver_); }
26 
27  virtual void handleRead(LayerStatus &status, const LayerState &current_state) {
28  if(current_state > Init){
29  if(!driver_->getState().isReady()) status.error("CAN not ready");
30  }
31  }
32  virtual void handleWrite(LayerStatus &status, const LayerState &current_state) {
33  if(current_state > Init){
34  if(!driver_->getState().isReady()) status.error("CAN not ready");
35  }
36  }
37 
38  virtual void handleDiag(LayerReport &report){
39  can::State s = driver_->getState();
40  if(!s.isReady()){
41  report.error("CAN layer not ready");
42  report.add("driver_state", int(s.driver_state));
43  }
44  if(s.error_code){
45  report.add("socket_error", s.error_code);
46  }
47  if(s.internal_error != 0){
48  report.add("internal_error", int(s.internal_error));
49  std::string desc;
50  if(driver_->translateError(s.internal_error, desc)) report.add("internal_error_desc", desc);
51  std::stringstream sstr;
52  sstr << std::hex;
53  {
54  boost::mutex::scoped_lock lock(mutex_);
55  for(size_t i=0; i < last_error_.dlc; ++i){
56  sstr << (unsigned int) last_error_.data[i] << " ";
57  }
58  }
59  report.add("can_error_frame", sstr.str());
60 
61  }
62 
63  }
64 
65  virtual void handleInit(LayerStatus &status){
66  if(thread_){
67  status.warn("CAN thread already running");
68  } else if(!driver_->init(device_, loopback_)) {
69  status.error("CAN init failed");
70  } else {
71  can::StateWaiter waiter(driver_.get());
72 
73  thread_.reset(new boost::thread(&can::DriverInterface::run, driver_));
74  error_listener_ = driver_->createMsgListener(can::ErrorHeader(), can::CommInterface::FrameDelegate(this, &CANLayer::handleFrame));
75 
76  if(!waiter.wait(can::State::ready, boost::posix_time::seconds(1))){
77  status.error("CAN init timed out");
78  }
79  }
80  if(!driver_->getState().isReady()){
81  status.error("CAN is not ready");
82  }
83  }
84  virtual void handleShutdown(LayerStatus &status){
85  can::StateWaiter waiter(driver_.get());
86  error_listener_.reset();
87  driver_->shutdown();
88  if(!waiter.wait(can::State::closed, boost::posix_time::seconds(1))){
89  status.warn("CAN shutdown timed out");
90  }
91  if(thread_){
92  thread_->interrupt();
93  thread_->join();
94  thread_.reset();
95  }
96  }
97 
98  virtual void handleHalt(LayerStatus &status) { /* nothing to do */ }
99 
100  virtual void handleRecover(LayerStatus &status){
101  if(!driver_->getState().isReady()){
102  handleShutdown(status);
103  handleInit(status);
104  }
105  }
106 
107 };
108 } // namespace canopen
109 
110 #endif
const bool loopback_
Definition: can_layer.h:13
boost::mutex mutex_
Definition: can_layer.h:10
CANLayer(const can::DriverInterfaceSharedPtr &driver, const std::string &device, bool loopback)
Definition: can_layer.h:24
const void warn(const std::string &r)
Definition: layer.h:43
virtual void run()=0
boost::array< value_type, 8 > data
virtual void handleRecover(LayerStatus &status)
Definition: can_layer.h:100
const std::string device_
Definition: can_layer.h:12
can::DriverInterfaceSharedPtr driver_
Definition: can_layer.h:11
virtual void handleInit(LayerStatus &status)
Definition: can_layer.h:65
can::FrameListenerConstSharedPtr error_listener_
Definition: can_layer.h:15
boost::shared_ptr< boost::thread > thread_
Definition: can_layer.h:21
#define LOG(log)
can::Frame last_error_
Definition: can_layer.h:14
boost::shared_ptr< DriverInterface > DriverInterfaceSharedPtr
CommInterface::FrameListenerConstSharedPtr FrameListenerConstSharedPtr
enum can::State::DriverState driver_state
virtual void handleWrite(LayerStatus &status, const LayerState &current_state)
Definition: can_layer.h:32
virtual bool isReady() const
void handleFrame(const can::Frame &msg)
Definition: can_layer.h:16
virtual void handleHalt(LayerStatus &status)
Definition: can_layer.h:98
virtual void handleShutdown(LayerStatus &status)
Definition: can_layer.h:84
virtual void handleRead(LayerStatus &status, const LayerState &current_state)
Definition: can_layer.h:27
void add(const std::string &key, const T &value)
Definition: layer.h:51
const void error(const std::string &r)
Definition: layer.h:44
virtual void handleDiag(LayerReport &report)
Definition: can_layer.h:38
unsigned int internal_error
unsigned char dlc
unsigned int id
boost::system::error_code error_code


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