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 
16 #include <cstring>
17 
20 
21 namespace can {
22 
23 class SocketCANInterface : public AsioDriver<boost::asio::posix::stream_descriptor> {
24  bool loopback_;
25  int sc_;
26  can_err_mask_t error_mask_, fatal_error_mask_;
27 
28  static can_err_mask_t parse_error_mask(SettingsConstSharedPtr settings, const std::string &entry, can_err_mask_t defaults) {
29  can_err_mask_t mask = 0;
30 
31  #define add_bit(e) mask |= (settings->get_optional(entry + "/" + #e, (defaults & e) != 0) ? e : 0)
32  add_bit(CAN_ERR_LOSTARB);
33  add_bit(CAN_ERR_CRTL);
34  add_bit(CAN_ERR_PROT);
35  add_bit(CAN_ERR_TRX);
36  add_bit(CAN_ERR_ACK);
37  add_bit(CAN_ERR_TX_TIMEOUT);
38  add_bit(CAN_ERR_BUSOFF);
39  add_bit(CAN_ERR_BUSERROR);
40  add_bit(CAN_ERR_RESTARTED);
41  #undef add_bit
42 
43  return mask;
44  }
45 public:
47  : loopback_(false), sc_(-1), error_mask_(0), fatal_error_mask_(0)
48  {}
49 
50  virtual bool doesLoopBack() const{
51  return loopback_;
52  }
53 
54  can_err_mask_t getErrorMask() const {
55  return error_mask_;
56  }
57 
58  can_err_mask_t getFatalErrorMask() const {
59  return fatal_error_mask_;
60  }
61  [[deprecated("provide settings explicitly")]] virtual bool init(const std::string &device, bool loopback) override {
62  return init(device, loopback, NoSettings::create());
63  }
64  virtual bool init(const std::string &device, bool loopback, SettingsConstSharedPtr settings) override {
65  if (!settings) {
66  ROSCANOPEN_ERROR("socketcan_interface", "settings must not be a null pointer");
67  return false;
68  }
69  const can_err_mask_t fatal_errors = ( CAN_ERR_TX_TIMEOUT /* TX timeout (by netdevice driver) */
70  | CAN_ERR_BUSOFF /* bus off */
71  | CAN_ERR_BUSERROR /* bus error (may flood!) */
72  | CAN_ERR_RESTARTED /* controller restarted */
73  );
74  const can_err_mask_t report_errors = ( CAN_ERR_LOSTARB /* lost arbitration / data[0] */
75  | CAN_ERR_CRTL /* controller problems / data[1] */
76  | CAN_ERR_PROT /* protocol violations / data[2..3] */
77  | CAN_ERR_TRX /* transceiver status / data[4] */
78  | CAN_ERR_ACK /* received no ACK on transmission */
79  );
80  can_err_mask_t fatal_error_mask = parse_error_mask(settings, "fatal_error_mask", fatal_errors) | CAN_ERR_BUSOFF;
81  can_err_mask_t error_mask = parse_error_mask(settings, "error_mask", report_errors | fatal_error_mask) | fatal_error_mask;
82  return init(device, loopback, error_mask, fatal_error_mask);
83  }
84 
85  virtual bool recover(){
86  if(!getState().isReady()){
87  shutdown();
89  }
90  return getState().isReady();
91  }
92  virtual bool translateError(unsigned int internal_error, std::string & str){
93 
94  bool ret = false;
95  if(!internal_error){
96  str = "OK";
97  ret = true;
98  }
99  if( internal_error & CAN_ERR_TX_TIMEOUT){
100  str += "TX timeout (by netdevice driver);";
101  ret = true;
102  }
103  if( internal_error & CAN_ERR_LOSTARB){
104  str += "lost arbitration;";
105  ret = true;
106  }
107  if( internal_error & CAN_ERR_CRTL){
108  str += "controller problems;";
109  ret = true;
110  }
111  if( internal_error & CAN_ERR_PROT){
112  str += "protocol violations;";
113  ret = true;
114  }
115  if( internal_error & CAN_ERR_TRX){
116  str += "transceiver status;";
117  ret = true;
118  }
119  if( internal_error & CAN_ERR_BUSOFF){
120  str += "bus off;";
121  ret = true;
122  }
123  if( internal_error & CAN_ERR_RESTARTED){
124  str += "controller restarted;";
125  ret = true;
126  }
127  return ret;
128  }
130  return sc_;
131  }
132 protected:
133  std::string device_;
134  can_frame frame_;
135 
136  bool init(const std::string &device, bool loopback, can_err_mask_t error_mask, can_err_mask_t fatal_error_mask) {
137  State s = getState();
138  if(s.driver_state == State::closed){
139  sc_ = 0;
140  device_ = device;
141  loopback_ = loopback;
142  error_mask_ = error_mask;
143  fatal_error_mask_ = fatal_error_mask;
144 
145  int sc = socket( PF_CAN, SOCK_RAW, CAN_RAW );
146  if(sc < 0){
147  setErrorCode(boost::system::error_code(sc,boost::system::system_category()));
148  return false;
149  }
150 
151  struct ifreq ifr;
152  strcpy(ifr.ifr_name, device_.c_str());
153  int ret = ioctl(sc, SIOCGIFINDEX, &ifr);
154 
155  if(ret != 0){
156  setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
157  close(sc);
158  return false;
159  }
160  ret = setsockopt(sc, SOL_CAN_RAW, CAN_RAW_ERR_FILTER,
161  &error_mask, sizeof(error_mask));
162 
163  if(ret != 0){
164  setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
165  close(sc);
166  return false;
167  }
168 
169  if(loopback_){
170  int recv_own_msgs = 1; /* 0 = disabled (default), 1 = enabled */
171  ret = setsockopt(sc, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &recv_own_msgs, sizeof(recv_own_msgs));
172 
173  if(ret != 0){
174  setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
175  close(sc);
176  return false;
177  }
178  }
179 
180  struct sockaddr_can addr = {0};
181  addr.can_family = AF_CAN;
182  addr.can_ifindex = ifr.ifr_ifindex;
183  ret = bind( sc, (struct sockaddr*)&addr, sizeof(addr) );
184 
185  if(ret != 0){
186  setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
187  close(sc);
188  return false;
189  }
190 
191  boost::system::error_code ec;
192  socket_.assign(sc,ec);
193 
194  setErrorCode(ec);
195 
196  if(ec){
197  close(sc);
198  return false;
199  }
200  setInternalError(0);
202  sc_ = sc;
203  return true;
204  }
205  return getState().isReady();
206  }
207 
208  virtual void triggerReadSome(){
209  boost::mutex::scoped_lock lock(send_mutex_);
210  socket_.async_read_some(boost::asio::buffer(&frame_, sizeof(frame_)), boost::bind( &SocketCANInterface::readFrame,this, boost::asio::placeholders::error));
211  }
212 
213  virtual bool enqueue(const Frame & msg){
214  boost::mutex::scoped_lock lock(send_mutex_); //TODO: timed try lock
215 
216  can_frame frame = {0};
217  frame.can_id = msg.id | (msg.is_extended?CAN_EFF_FLAG:0) | (msg.is_rtr?CAN_RTR_FLAG:0);;
218  frame.can_dlc = msg.dlc;
219 
220 
221  for(int i=0; i < frame.can_dlc;++i)
222  frame.data[i] = msg.data[i];
223 
224  boost::system::error_code ec;
225  boost::asio::write(socket_, boost::asio::buffer(&frame, sizeof(frame)),boost::asio::transfer_all(), ec);
226  if(ec){
227  ROSCANOPEN_ERROR("socketcan_interface", "FAILED " << ec);
228  setErrorCode(ec);
229  setNotReady();
230  return false;
231  }
232 
233  return true;
234  }
235 
236  void readFrame(const boost::system::error_code& error){
237  if(!error){
238  input_.dlc = frame_.can_dlc;
239  for(int i=0;i<frame_.can_dlc && i < 8; ++i){
240  input_.data[i] = frame_.data[i];
241  }
242 
243  if(frame_.can_id & CAN_ERR_FLAG){ // error message
244  input_.id = frame_.can_id & CAN_EFF_MASK;
245  input_.is_error = 1;
246 
247  if (frame_.can_id & fatal_error_mask_) {
248  ROSCANOPEN_ERROR("socketcan_interface", "internal error: " << input_.id);
250  setNotReady();
251  }
252  }else{
253  input_.is_extended = (frame_.can_id & CAN_EFF_FLAG) ? 1 :0;
254  input_.id = frame_.can_id & (input_.is_extended ? CAN_EFF_MASK : CAN_SFF_MASK);
255  input_.is_error = 0;
256  input_.is_rtr = (frame_.can_id & CAN_RTR_FLAG) ? 1 : 0;
257  }
258 
259  }
260  frameReceived(error);
261  }
262 private:
263  boost::mutex send_mutex_;
264 };
265 
267 using SocketCANDriverSharedPtr = std::shared_ptr<SocketCANDriver>;
268 using SocketCANInterfaceSharedPtr = std::shared_ptr<SocketCANInterface>;
269 
270 template <typename T> class ThreadedInterface;
272 using ThreadedSocketCANInterfaceSharedPtr = std::shared_ptr<ThreadedSocketCANInterface>;
273 
274 
275 } // namespace can
276 #endif
can::AsioDriver< boost::asio::posix::stream_descriptor >::setInternalError
void setInternalError(unsigned int internal_error)
Definition: asio_base.h:47
can::NoSettings::create
static SettingsConstSharedPtr create()
Definition: settings.h:36
can::SocketCANInterface::triggerReadSome
virtual void triggerReadSome()
Definition: socketcan.h:208
can::SocketCANInterface::getErrorMask
can_err_mask_t getErrorMask() const
Definition: socketcan.h:54
can::AsioDriver< boost::asio::posix::stream_descriptor >::shutdown
virtual void shutdown()
Definition: asio_base.h:111
can::Frame
Definition: interface.h:62
can::State::open
@ open
Definition: interface.h:89
can::Header::is_extended
unsigned int is_extended
frame uses 29 bit CAN identifier
Definition: interface.h:26
can::AsioDriver< boost::asio::posix::stream_descriptor >::setNotReady
void setNotReady()
Definition: asio_base.h:62
can::SocketCANInterface::loopback_
bool loopback_
Definition: socketcan.h:24
string.h
dispatcher.h
can::SocketCANInterface::getFatalErrorMask
can_err_mask_t getFatalErrorMask() const
Definition: socketcan.h:58
can::SocketCANInterface::getInternalSocket
int getInternalSocket()
Definition: socketcan.h:129
can::ThreadedSocketCANInterfaceSharedPtr
std::shared_ptr< ThreadedSocketCANInterface > ThreadedSocketCANInterfaceSharedPtr
Definition: socketcan.h:272
can::Frame::dlc
unsigned char dlc
len of data
Definition: interface.h:65
can::State::closed
@ closed
Definition: interface.h:89
can::AsioDriver< boost::asio::posix::stream_descriptor >::input_
Frame input_
Definition: asio_base.h:32
can::SocketCANInterface::enqueue
virtual bool enqueue(const Frame &msg)
Definition: socketcan.h:213
can::SocketCANInterface::init
virtual bool init(const std::string &device, bool loopback, SettingsConstSharedPtr settings) override
Definition: socketcan.h:64
can::SocketCANInterface::init
bool init(const std::string &device, bool loopback, can_err_mask_t error_mask, can_err_mask_t fatal_error_mask)
Definition: socketcan.h:136
can::SocketCANDriverSharedPtr
std::shared_ptr< SocketCANDriver > SocketCANDriverSharedPtr
Definition: socketcan.h:267
can::SocketCANInterface::recover
virtual bool recover()
Definition: socketcan.h:85
can::AsioDriver< boost::asio::posix::stream_descriptor >::getState
State getState()
Definition: asio_base.h:83
can::SocketCANInterface::fatal_error_mask_
can_err_mask_t fatal_error_mask_
Definition: socketcan.h:26
can::SocketCANInterface::sc_
int sc_
Definition: socketcan.h:25
add_bit
#define add_bit(e)
can::Header::is_rtr
unsigned int is_rtr
frame is a remote transfer request
Definition: interface.h:25
can::SocketCANInterface::device_
std::string device_
Definition: socketcan.h:133
ROSCANOPEN_ERROR
#define ROSCANOPEN_ERROR(name, args)
Definition: logging.h:9
can::AsioDriver< boost::asio::posix::stream_descriptor >::setErrorCode
void setErrorCode(const boost::system::error_code &error)
Definition: asio_base.h:40
can::SocketCANInterface::frame_
can_frame frame_
Definition: socketcan.h:134
can::ThreadedInterface
Definition: socketcan.h:270
can::Header::id
unsigned int id
CAN ID (11 or 29 bits valid, depending on is_extended member.
Definition: interface.h:23
can::SocketCANInterface::send_mutex_
boost::mutex send_mutex_
Definition: socketcan.h:263
can::Frame::data
std::array< value_type, 8 > data
array for 8 data bytes with bounds checking
Definition: interface.h:64
can::SettingsConstSharedPtr
std::shared_ptr< const Settings > SettingsConstSharedPtr
Definition: settings.h:31
can::State::isReady
virtual bool isReady() const
Definition: interface.h:95
can
Definition: asio_base.h:11
can::SocketCANInterface::SocketCANInterface
SocketCANInterface()
Definition: socketcan.h:46
can::SocketCANInterface::translateError
virtual bool translateError(unsigned int internal_error, std::string &str)
Definition: socketcan.h:92
can::SocketCANInterface::readFrame
void readFrame(const boost::system::error_code &error)
Definition: socketcan.h:236
can::AsioDriver< boost::asio::posix::stream_descriptor >::setDriverState
void setDriverState(State::DriverState state)
Definition: asio_base.h:55
asio_base.h
can::AsioDriver
Definition: asio_base.h:14
can::SocketCANInterface::error_mask_
can_err_mask_t error_mask_
Definition: socketcan.h:26
can::Header::is_error
unsigned int is_error
marks an error frame (only used internally)
Definition: interface.h:24
can::State
Definition: interface.h:86
can::State::driver_state
enum can::State::DriverState driver_state
can::SocketCANInterface
Definition: socketcan.h:23
can::AsioDriver< boost::asio::posix::stream_descriptor >::frameReceived
void frameReceived(const boost::system::error_code &error)
Definition: asio_base.h:66
can::SocketCANInterface::parse_error_mask
static can_err_mask_t parse_error_mask(SettingsConstSharedPtr settings, const std::string &entry, can_err_mask_t defaults)
Definition: socketcan.h:28
can::SocketCANInterface::doesLoopBack
virtual bool doesLoopBack() const
Definition: socketcan.h:50
can::AsioDriver< boost::asio::posix::stream_descriptor >::socket_
boost::asio::posix::stream_descriptor socket_
Definition: asio_base.h:31
can::SocketCANInterface::init
virtual bool init(const std::string &device, bool loopback) override
Definition: socketcan.h:61
can::SocketCANInterfaceSharedPtr
std::shared_ptr< SocketCANInterface > SocketCANInterfaceSharedPtr
Definition: socketcan.h:268


socketcan_interface
Author(s): Mathias Lüdtke
autogenerated on Wed Mar 2 2022 00:52:25