bcm.h
Go to the documentation of this file.
1 #ifndef H_CAN_BCM
2 #define H_CAN_BCM
3 
5 
6 #include <sys/types.h>
7 #include <sys/socket.h>
8 #include <sys/ioctl.h>
9 #include <net/if.h>
10 
11 #include <linux/can.h>
12 #include <linux/can/bcm.h>
13 #include <linux/can/error.h>
14 
15 #include <cstring>
16 
17 #include <boost/chrono.hpp>
18 
19 namespace can {
20 
21 class BCMsocket{
22  int s_;
23  struct Message {
24  size_t size;
25  uint8_t *data;
26  Message(size_t n)
27  : size(sizeof(bcm_msg_head) + sizeof(can_frame)*n), data(new uint8_t[size])
28  {
29  assert(n<=256);
30  std::memset(data, 0, size);
31  head().nframes = n;
32  }
33  bcm_msg_head& head() {
34  return *(bcm_msg_head*)data;
35  }
36  template<typename T> void setIVal2(T period){
37  long long usec = boost::chrono::duration_cast<boost::chrono::microseconds>(period).count();
38  head().ival2.tv_sec = usec / 1000000;
39  head().ival2.tv_usec = usec % 1000000;
40  }
41  void setHeader(Header header){
42  head().can_id = header.id | (header.is_extended?CAN_EFF_FLAG:0);
43  }
44  bool write(int s){
45  return ::write(s, data, size) > 0;
46  }
48  delete[] data;
49  data = 0;
50  size = 0;
51  }
52  };
53 public:
54  BCMsocket():s_(-1){
55  }
56  bool init(const std::string &device){
57  s_ = socket(PF_CAN, SOCK_DGRAM, CAN_BCM);
58 
59  if(s_ < 0 ) return false;
60  struct ifreq ifr;
61  std::strcpy(ifr.ifr_name, device.c_str());
62  int ret = ioctl(s_, SIOCGIFINDEX, &ifr);
63 
64  if(ret != 0){
65  shutdown();
66  return false;
67  }
68 
69  struct sockaddr_can addr = {0};
70  addr.can_family = AF_CAN;
71  addr.can_ifindex = ifr.ifr_ifindex;
72 
73  ret = connect(s_, (struct sockaddr *)&addr, sizeof(addr));
74 
75  if(ret < 0){
76  shutdown();
77  return false;
78  }
79  return true;
80  }
81  template<typename DurationType> bool startTX(DurationType period, Header header, size_t num, Frame *frames) {
82  Message msg(num);
83  msg.setHeader(header);
84  msg.setIVal2(period);
85 
86  bcm_msg_head &head = msg.head();
87 
88  head.opcode = TX_SETUP;
89  head.flags |= SETTIMER | STARTTIMER;
90 
91  for(size_t i=0; i < num; ++i){ // msg nr
92  head.frames[i].can_dlc = frames[i].dlc;
93  head.frames[i].can_id = head.can_id;
94  for(size_t j = 0; j < head.frames[i].can_dlc; ++j){ // byte nr
95  head.frames[i].data[j] = frames[i].data[j];
96  }
97  }
98  return msg.write(s_);
99  }
100  bool stopTX(Header header){
101  Message msg(0);
102  msg.head().opcode = TX_DELETE;
103  msg.setHeader(header);
104  return msg.write(s_);
105  }
106  void shutdown(){
107  if(s_ > 0){
108  close(s_);
109  s_ = -1;
110  }
111  }
112 
113  virtual ~BCMsocket(){
114  shutdown();
115  }
116 };
117 
118 }
119 
120 #endif
std::array< value_type, 8 > data
array for 8 data bytes with bounds checking
Definition: interface.h:64
bool stopTX(Header header)
Definition: bcm.h:100
Definition: asio_base.h:11
void setHeader(Header header)
Definition: bcm.h:41
unsigned int is_extended
frame uses 29 bit CAN identifier
Definition: interface.h:26
bool write(int s)
Definition: bcm.h:44
virtual ~BCMsocket()
Definition: bcm.h:113
int s_
Definition: bcm.h:22
bcm_msg_head & head()
Definition: bcm.h:33
bool init(const std::string &device)
Definition: bcm.h:56
uint8_t * data
Definition: bcm.h:25
void setIVal2(T period)
Definition: bcm.h:36
void shutdown()
Definition: bcm.h:106
BCMsocket()
Definition: bcm.h:54
bool startTX(DurationType period, Header header, size_t num, Frame *frames)
Definition: bcm.h:81
unsigned char dlc
len of data
Definition: interface.h:65
unsigned int id
CAN ID (11 or 29 bits valid, depending on is_extended member.
Definition: interface.h:23
Message(size_t n)
Definition: bcm.h:26


socketcan_interface
Author(s): Mathias Lüdtke
autogenerated on Mon Feb 28 2022 23:28:00