socketcan.h
Go to the documentation of this file.
1 #ifndef H_SOCKETCAN_DRIVER
2 #define H_SOCKETCAN_DRIVER
3 
5 #include <boost/bind.hpp>
6 
7 #include <sys/types.h>
8 #include <sys/socket.h>
9 #include <sys/ioctl.h>
10 #include <net/if.h>
11 
12 #include <linux/can.h>
13 #include <linux/can/raw.h>
14 #include <linux/can/error.h>
15 
17 
18 namespace can {
19 
20 class SocketCANInterface : public AsioDriver<boost::asio::posix::stream_descriptor> {
21  bool loopback_;
22  int sc_;
23 public:
25  : loopback_(false), sc_(-1)
26  {}
27 
28  virtual bool doesLoopBack() const{
29  return loopback_;
30  }
31 
32  virtual bool init(const std::string &device, bool loopback){
33  State s = getState();
34  if(s.driver_state == State::closed){
35  sc_ = 0;
36  device_ = device;
37  loopback_ = loopback;
38 
39  int sc = socket( PF_CAN, SOCK_RAW, CAN_RAW );
40  if(sc < 0){
41  setErrorCode(boost::system::error_code(sc,boost::system::system_category()));
42  return false;
43  }
44 
45  struct ifreq ifr;
46  strcpy(ifr.ifr_name, device_.c_str());
47  int ret = ioctl(sc, SIOCGIFINDEX, &ifr);
48 
49  if(ret != 0){
50  setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
51  close(sc);
52  return false;
53  }
54  can_err_mask_t err_mask =
55  ( CAN_ERR_TX_TIMEOUT /* TX timeout (by netdevice driver) */
56  | CAN_ERR_LOSTARB /* lost arbitration / data[0] */
57  | CAN_ERR_CRTL /* controller problems / data[1] */
58  | CAN_ERR_PROT /* protocol violations / data[2..3] */
59  | CAN_ERR_TRX /* transceiver status / data[4] */
60  | CAN_ERR_ACK /* received no ACK on transmission */
61  | CAN_ERR_BUSOFF /* bus off */
62  //CAN_ERR_BUSERROR /* bus error (may flood!) */
63  | CAN_ERR_RESTARTED /* controller restarted */
64  );
65 
66  ret = setsockopt(sc, SOL_CAN_RAW, CAN_RAW_ERR_FILTER,
67  &err_mask, sizeof(err_mask));
68 
69  if(ret != 0){
70  setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
71  close(sc);
72  return false;
73  }
74 
75  if(loopback_){
76  int recv_own_msgs = 1; /* 0 = disabled (default), 1 = enabled */
77  ret = setsockopt(sc, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &recv_own_msgs, sizeof(recv_own_msgs));
78 
79  if(ret != 0){
80  setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
81  close(sc);
82  return false;
83  }
84  }
85 
86  struct sockaddr_can addr = {0};
87  addr.can_family = AF_CAN;
88  addr.can_ifindex = ifr.ifr_ifindex;
89  ret = bind( sc, (struct sockaddr*)&addr, sizeof(addr) );
90 
91  if(ret != 0){
92  setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
93  close(sc);
94  return false;
95  }
96 
97  boost::system::error_code ec;
98  socket_.assign(sc,ec);
99 
100  setErrorCode(ec);
101 
102  if(ec){
103  close(sc);
104  return false;
105  }
106  setInternalError(0);
108  sc_ = sc;
109  return true;
110  }
111  return getState().isReady();
112  }
113  virtual bool recover(){
114  if(!getState().isReady()){
115  shutdown();
116  return init(device_, doesLoopBack());
117  }
118  return getState().isReady();
119  }
120  virtual bool translateError(unsigned int internal_error, std::string & str){
121 
122  bool ret = false;
123  if(!internal_error){
124  str = "OK";
125  ret = true;
126  }
127  if( internal_error & CAN_ERR_TX_TIMEOUT){
128  str += "TX timeout (by netdevice driver);";
129  ret = true;
130  }
131  if( internal_error & CAN_ERR_LOSTARB){
132  str += "lost arbitration;";
133  ret = true;
134  }
135  if( internal_error & CAN_ERR_CRTL){
136  str += "controller problems;";
137  ret = true;
138  }
139  if( internal_error & CAN_ERR_PROT){
140  str += "protocol violations;";
141  ret = true;
142  }
143  if( internal_error & CAN_ERR_TRX){
144  str += "transceiver status;";
145  ret = true;
146  }
147  if( internal_error & CAN_ERR_BUSOFF){
148  str += "bus off;";
149  ret = true;
150  }
151  if( internal_error & CAN_ERR_RESTARTED){
152  str += "ontroller restarted;";
153  ret = true;
154  }
155  return ret;
156  }
158  return sc_;
159  }
160 protected:
161  std::string device_;
162  can_frame frame_;
163 
164  virtual void triggerReadSome(){
165  boost::mutex::scoped_lock lock(send_mutex_);
166  socket_.async_read_some(boost::asio::buffer(&frame_, sizeof(frame_)), boost::bind( &SocketCANInterface::readFrame,this, boost::asio::placeholders::error));
167  }
168 
169  virtual bool enqueue(const Frame & msg){
170  boost::mutex::scoped_lock lock(send_mutex_); //TODO: timed try lock
171 
172  can_frame frame = {0};
173  frame.can_id = msg.id | (msg.is_extended?CAN_EFF_FLAG:0) | (msg.is_rtr?CAN_RTR_FLAG:0);;
174  frame.can_dlc = msg.dlc;
175 
176 
177  for(int i=0; i < frame.can_dlc;++i)
178  frame.data[i] = msg.data[i];
179 
180  boost::system::error_code ec;
181  boost::asio::write(socket_, boost::asio::buffer(&frame, sizeof(frame)),boost::asio::transfer_all(), ec);
182  if(ec){
183  LOG("FAILED " << ec);
184  setErrorCode(ec);
185  setNotReady();
186  return false;
187  }
188 
189  return true;
190  }
191 
192  void readFrame(const boost::system::error_code& error){
193  if(!error){
194  input_.dlc = frame_.can_dlc;
195  for(int i=0;i<frame_.can_dlc && i < 8; ++i){
196  input_.data[i] = frame_.data[i];
197  }
198 
199  if(frame_.can_id & CAN_ERR_FLAG){ // error message
200  input_.id = frame_.can_id & CAN_EFF_MASK;
201  input_.is_error = 1;
202 
203  LOG("error: " << input_.id);
205  setNotReady();
206 
207  }else{
208  input_.is_extended = (frame_.can_id & CAN_EFF_FLAG) ? 1 :0;
209  input_.id = frame_.can_id & (input_.is_extended ? CAN_EFF_MASK : CAN_SFF_MASK);
210  input_.is_error = 0;
211  input_.is_rtr = (frame_.can_id & CAN_RTR_FLAG) ? 1 : 0;
212  }
213 
214  }
215  frameReceived(error);
216  }
217 private:
218  boost::mutex send_mutex_;
219 };
220 
222 typedef boost::shared_ptr<SocketCANDriver> SocketCANDriverSharedPtr;
223 typedef boost::shared_ptr<SocketCANInterface> SocketCANInterfaceSharedPtr;
224 
225 template <typename T> class ThreadedInterface;
227 typedef boost::shared_ptr<ThreadedSocketCANInterface> ThreadedSocketCANInterfaceSharedPtr;
228 
229 
230 } // namespace can
231 #endif
virtual bool translateError(unsigned int internal_error, std::string &str)
Definition: socketcan.h:120
boost::mutex send_mutex_
Definition: socketcan.h:218
virtual bool init(const std::string &device, bool loopback)
Definition: socketcan.h:32
virtual bool doesLoopBack() const
Definition: socketcan.h:28
virtual bool recover()
Definition: socketcan.h:113
unsigned int is_error
marks an error frame (only used internally)
Definition: interface.h:20
Definition: asio_base.h:11
void setInternalError(unsigned int internal_error)
Definition: asio_base.h:47
boost::array< value_type, 8 > data
array for 8 data bytes with bounds checking
Definition: interface.h:58
boost::shared_ptr< SocketCANInterface > SocketCANInterfaceSharedPtr
Definition: socketcan.h:223
unsigned int is_extended
frame uses 29 bit CAN identifier
Definition: interface.h:22
#define LOG(log)
Definition: interface.h:216
SocketCANInterface SocketCANDriver
Definition: socketcan.h:221
virtual void triggerReadSome()
Definition: socketcan.h:164
ThreadedInterface< SocketCANInterface > ThreadedSocketCANInterface
Definition: socketcan.h:225
void setErrorCode(const boost::system::error_code &error)
Definition: asio_base.h:40
enum can::State::DriverState driver_state
boost::shared_ptr< ThreadedSocketCANInterface > ThreadedSocketCANInterfaceSharedPtr
Definition: socketcan.h:227
virtual bool isReady() const
Definition: interface.h:89
void readFrame(const boost::system::error_code &error)
Definition: socketcan.h:192
void frameReceived(const boost::system::error_code &error)
Definition: asio_base.h:66
virtual bool enqueue(const Frame &msg)
Definition: socketcan.h:169
boost::shared_ptr< SocketCANDriver > SocketCANDriverSharedPtr
Definition: socketcan.h:222
unsigned char dlc
len of data
Definition: interface.h:59
unsigned int id
CAN ID (11 or 29 bits valid, depending on is_extended member.
Definition: interface.h:19
unsigned int is_rtr
frame is a remote transfer request
Definition: interface.h:21
boost::asio::posix::stream_descriptor socket_
Definition: asio_base.h:31


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