-
Notifications
You must be signed in to change notification settings - Fork 2
Expand file tree
/
Copy pathsocketcan_cpp.cpp
More file actions
209 lines (180 loc) · 6.4 KB
/
socketcan_cpp.cpp
File metadata and controls
209 lines (180 loc) · 6.4 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
#include "socketcan_cpp/socketcan_cpp.hpp"
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#ifdef HAVE_SOCKETCAN_HEADERS
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <net/if.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <linux/can/raw.h>
/* CAN DLC to real data length conversion helpers */
static const unsigned char dlc2len[] = {0, 1, 2, 3, 4, 5, 6, 7,
8, 12, 16, 20, 24, 32, 48, 64};
/* get data length from can_dlc with sanitized can_dlc */
unsigned char can_dlc2len(unsigned char can_dlc)
{
return dlc2len[can_dlc & 0x0F];
}
static const unsigned char len2dlc[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, /* 0 - 8 */
9, 9, 9, 9, /* 9 - 12 */
10, 10, 10, 10, /* 13 - 16 */
11, 11, 11, 11, /* 17 - 20 */
12, 12, 12, 12, /* 21 - 24 */
13, 13, 13, 13, 13, 13, 13, 13, /* 25 - 32 */
14, 14, 14, 14, 14, 14, 14, 14, /* 33 - 40 */
14, 14, 14, 14, 14, 14, 14, 14, /* 41 - 48 */
15, 15, 15, 15, 15, 15, 15, 15, /* 49 - 56 */
15, 15, 15, 15, 15, 15, 15, 15}; /* 57 - 64 */
/* map the sanitized data length to an appropriate data length code */
unsigned char can_len2dlc(unsigned char len)
{
if (len > 64)
return 0xF;
return len2dlc[len];
}
#endif
namespace scpp
{
SocketCan::SocketCan() {}
SocketCanStatus SocketCan::open(const std::string & can_interface, int32_t read_timeout_ms, SocketMode mode)
{
m_interface = can_interface;
m_socket_mode = mode;
m_read_timeout_ms = read_timeout_ms;
#ifdef HAVE_SOCKETCAN_HEADERS
/* open socket */
if ((m_socket = socket(PF_CAN, SOCK_RAW, CAN_RAW)) < 0)
{
perror("socket");
return STATUS_SOCKET_CREATE_ERROR;
}
int mtu, enable_canfd = 1;
struct sockaddr_can addr;
struct ifreq ifr;
strncpy(ifr.ifr_name, can_interface.c_str(), IFNAMSIZ - 1);
ifr.ifr_name[IFNAMSIZ - 1] = '\0';
ifr.ifr_ifindex = if_nametoindex(ifr.ifr_name);
if (!ifr.ifr_ifindex) {
perror("if_nametoindex");
return STATUS_INTERFACE_NAME_TO_IDX_ERROR;
}
addr.can_family = AF_CAN;
addr.can_ifindex = ifr.ifr_ifindex;
if (mode == MODE_CANFD_MTU)
{
/* check if the frame fits into the CAN netdevice */
if (ioctl(m_socket, SIOCGIFMTU, &ifr) < 0) {
perror("SIOCGIFMTU");
return STATUS_MTU_ERROR;
}
mtu = ifr.ifr_mtu;
if (mtu != CANFD_MTU) {
return STATUS_CANFD_NOT_SUPPORTED;
}
/* interface is ok - try to switch the socket into CAN FD mode */
if (setsockopt(m_socket, SOL_CAN_RAW, CAN_RAW_FD_FRAMES,
&enable_canfd, sizeof(enable_canfd)))
{
return STATUS_ENABLE_FD_SUPPORT_ERROR;
}
}
//const int timestamping_flags = (SOF_TIMESTAMPING_SOFTWARE | \
// SOF_TIMESTAMPING_RX_SOFTWARE | \
// SOF_TIMESTAMPING_RAW_HARDWARE);
//if (setsockopt(m_socket, SOL_SOCKET, SO_TIMESTAMPING,
// ×tamping_flags, sizeof(timestamping_flags)) < 0) {
// perror("setsockopt SO_TIMESTAMPING is not supported by your Linux kernel");
//}
///* disable default receive filter on this RAW socket */
///* This is obsolete as we do not read from the socket at all, but for */
///* this reason we can remove the receive list in the Kernel to save a */
///* little (really a very little!) CPU usage. */
//setsockopt(s, SOL_CAN_RAW, CAN_RAW_FILTER, NULL, 0);
// LINUX
struct timeval tv;
tv.tv_sec = 0; /* 30 Secs Timeout */
tv.tv_usec = m_read_timeout_ms * 1000; // Not init'ing this can cause strange errors
setsockopt(m_socket, SOL_SOCKET, SO_RCVTIMEO, (const char*)&tv,sizeof(struct timeval));
if (bind(m_socket, (struct sockaddr *)&addr, sizeof(addr)) < 0) {
perror("bind");
return STATUS_BIND_ERROR;
}
struct can_filter rfilter[1];
rfilter[0].can_id = ~0x00000700;
rfilter[0].can_mask = 0x1FFFFF00;
if (setsockopt(m_socket, SOL_CAN_RAW, CAN_RAW_FILTER, &rfilter, sizeof(rfilter)) < 0) {
perror("setsockopt");
return STATUS_SOCKET_CREATE_ERROR; // You should define this status
}
#else
printf("Your operating system does not support socket can! \n");
#endif
return STATUS_OK;
}
SocketCanStatus SocketCan::write(const CanFrame & msg)
{
#ifdef HAVE_SOCKETCAN_HEADERS
struct canfd_frame frame;
memset(&frame, 0, sizeof(frame)); /* init CAN FD frame, e.g. LEN = 0 */
//convert CanFrame to canfd_frame
frame.can_id = msg.id;
if (msg.id > 0x7FF) {
frame.can_id |= CAN_EFF_FLAG; // Set extended frame format bit
}
frame.len = msg.len;
frame.flags = msg.flags;
memcpy(frame.data, msg.data, msg.len);
if (m_socket_mode == MODE_CANFD_MTU)
{
/* ensure discrete CAN FD length values 0..8, 12, 16, 20, 24, 32, 64 */
frame.len = can_dlc2len(can_len2dlc(frame.len));
}
/* send frame */
if (::write(m_socket, &frame, int(m_socket_mode)) != int(m_socket_mode)) {
perror("write");
return STATUS_WRITE_ERROR;
}
#else
printf("Your operating system does not support socket can! \n");
#endif
return STATUS_OK;
}
SocketCanStatus SocketCan::read(CanFrame & msg)
{
#ifdef HAVE_SOCKETCAN_HEADERS
struct canfd_frame frame;
auto num_bytes = ::read(m_socket, &frame, CANFD_MTU);
if (num_bytes != CAN_MTU && num_bytes != CANFD_MTU)
{
perror("Can read error");
return STATUS_READ_ERROR;
}
msg.id = frame.can_id;
msg.len = frame.len;
msg.flags = frame.flags;
memcpy(msg.data, frame.data, frame.len);
#else
printf("Your operating system does not support socket can! \n");
#endif
return STATUS_OK;
}
SocketCanStatus SocketCan::close()
{
#ifdef HAVE_SOCKETCAN_HEADERS
::close(m_socket);
#endif
return STATUS_OK;
}
const std::string & SocketCan::interfaceName() const
{
return m_interface;
}
SocketCan::~SocketCan()
{
close();
}
}