socketcan.py
Go to the documentation of this file.
1 #
2 # Copyright (C) 2014-2016 UAVCAN Development Team <uavcan.org>
3 #
4 # This software is distributed under the terms of the MIT License.
5 #
6 # Author: Ben Dyer <ben_dyer@mac.com>
7 # Pavel Kirienko <pavel.kirienko@zubax.com>
8 #
9 
10 from __future__ import division, absolute_import, print_function, unicode_literals
11 import os
12 import errno
13 import fcntl
14 import socket
15 import struct
16 import select
17 import time
18 import threading
19 from logging import getLogger
20 
21 from .common import DriverError, TxQueueFullError, CANFrame, AbstractDriver
22 from .timestamp_estimator import TimestampEstimator
23 
24 try:
25  import queue
26 except ImportError:
27  # noinspection PyPep8Naming,PyUnresolvedReferences
28  import Queue as queue
29 
30 logger = getLogger(__name__)
31 
32 
33 # Python 3.3+'s socket module has support for SocketCAN when running on Linux. Use that if possible.
34 # noinspection PyBroadException
35 try:
36  # noinspection PyStatementEffect
37  socket.CAN_RAW
38 
39  def get_socket(ifname):
40  s = socket.socket(socket.PF_CAN, socket.SOCK_RAW, socket.CAN_RAW)
41  s.bind((ifname, ))
42  return s
43 
44  NATIVE_SOCKETCAN = True
45 except Exception:
46  NATIVE_SOCKETCAN = False
47 
48  import ctypes
49  import ctypes.util
50 
51  libc = ctypes.CDLL(ctypes.util.find_library("c"), use_errno=True)
52 
53  # from linux/can.h
54  CAN_RAW = 1
55 
56  # from linux/socket.h
57  AF_CAN = 29
58 
59  from socket import SOL_SOCKET
60 
61  SOL_CAN_BASE = 100
62  SOL_CAN_RAW = SOL_CAN_BASE + CAN_RAW
63  CAN_RAW_FILTER = 1 # set 0 .. n can_filter(s)
64  CAN_RAW_ERR_FILTER = 2 # set filter for error frames
65  CAN_RAW_LOOPBACK = 3 # local loopback (default:on)
66  CAN_RAW_RECV_OWN_MSGS = 4 # receive my own msgs (default:off)
67  CAN_RAW_FD_FRAMES = 5 # allow CAN FD frames (default:off)
68 
69  # noinspection PyPep8Naming
70  class sockaddr_can(ctypes.Structure):
71  """
72  typedef __u32 canid_t;
73  struct sockaddr_can {
74  sa_family_t can_family;
75  int can_ifindex;
76  union {
77  struct { canid_t rx_id, tx_id; } tp;
78  } can_addr;
79  };
80  """
81  _fields_ = [
82  ("can_family", ctypes.c_uint16),
83  ("can_ifindex", ctypes.c_int),
84  ("can_addr_tp_rx_id", ctypes.c_uint32),
85  ("can_addr_tp_tx_id", ctypes.c_uint32)
86  ]
87 
88  # noinspection PyPep8Naming
89  class can_frame(ctypes.Structure):
90  """
91  typedef __u32 canid_t;
92  struct can_frame {
93  canid_t can_id;
94  __u8 can_dlc;
95  __u8 data[8] __attribute__((aligned(8)));
96  };
97  """
98  _fields_ = [
99  ("can_id", ctypes.c_uint32),
100  ("can_dlc", ctypes.c_uint8),
101  ("_pad", ctypes.c_ubyte * 3),
102  ("data", ctypes.c_uint8 * 8)
103  ]
104 
105 
106  class CANSocket(object):
107  def __init__(self, fd):
108  if fd < 0:
109  raise DriverError('Invalid socket fd')
110  self.fd = fd
111 
112  def recv(self, bufsize):
113  buf = ctypes.create_string_buffer(bufsize)
114  nbytes = libc.read(self.fd, ctypes.byref(buf), bufsize)
115  return buf[0:nbytes]
116 
117  def send(self, data):
118  frame = can_frame()
119  ctypes.memmove(ctypes.byref(frame), data, ctypes.sizeof(frame))
120  return libc.write(self.fd, ctypes.byref(frame), ctypes.sizeof(frame))
121 
122  def fileno(self):
123  return self.fd
124 
125  def close(self):
126  libc.close(self.fd)
127 
128  def get_socket(ifname):
129  socket_fd = libc.socket(AF_CAN, socket.SOCK_RAW, CAN_RAW)
130  if socket_fd < 0:
131  raise DriverError('Could not open socket')
132 
133  libc.fcntl(socket_fd, fcntl.F_SETFL, os.O_NONBLOCK)
134 
135  ifidx = libc.if_nametoindex(ifname)
136  if ctypes.get_errno() != 0:
137  raise DriverError('Could not determine iface index [errno %s]' % ctypes.get_errno())
138 
139  addr = sockaddr_can(AF_CAN, ifidx)
140  error = libc.bind(socket_fd, ctypes.byref(addr), ctypes.sizeof(addr))
141  if error != 0:
142  raise DriverError('Could not bind socket [errno %s]' % ctypes.get_errno())
143 
144  return CANSocket(socket_fd)
145 
146 
147 # from linux/can.h
148 CAN_EFF_FLAG = 0x80000000
149 CAN_EFF_MASK = 0x1FFFFFFF
150 
151 SO_TIMESTAMP = 29
152 
153 
155  FRAME_FORMAT = '=IB3x8s'
156  FRAME_SIZE = 16
157  TIMEVAL_FORMAT = '@LL'
158  TX_QUEUE_SIZE = 1000
159 
160  def __init__(self, interface, **_extras):
161  super(SocketCAN, self).__init__()
162 
163  self.socket = get_socket(interface)
164 
165  self._poll_rx = select.poll()
166  self._poll_rx.register(self.socket.fileno(), select.POLLIN | select.POLLPRI | select.POLLERR)
167 
169  self._write_queue = queue.Queue(self.TX_QUEUE_SIZE)
170  self._write_feedback_queue = queue.Queue()
171 
172  self._writer_thread = threading.Thread(target=self._writer_thread_loop, name='socketcan_writer')
173  self._writer_thread.daemon = True
174  self._writer_thread.start()
175 
176  # Timestamping
177  if NATIVE_SOCKETCAN:
178  self.socket.setsockopt(socket.SOL_SOCKET, SO_TIMESTAMP, 1)
179 
180  ppm = lambda x: x / 1e6
181  milliseconds = lambda x: x * 1e-3
182 
183  # We're using this thing to estimate the difference between monotonic and real clocks
184  # See http://stackoverflow.com/questions/35426864 (at the time of writing the question was unanswered)
185  self._mono_to_real_estimator = TimestampEstimator(max_rate_error=ppm(100),
186  fixed_delay=milliseconds(0.001),
187  max_phase_error_to_resync=milliseconds(50))
188 
189  def _convert_real_to_monotonic(self, value):
190  mono = time.monotonic() # est_real is the best guess about real timestamp here
191  real = time.time()
192  est_real = self._mono_to_real_estimator.update(mono, real)
193  mono_to_real_offset = est_real - mono
194  return value - mono_to_real_offset
195 
197  while not self._writer_thread_should_stop:
198  try:
199  frame = self._write_queue.get(timeout=0.1)
200  except queue.Empty:
201  continue
202 
203  try:
204  while not self._writer_thread_should_stop:
205  try:
206  message_id = frame.id | (CAN_EFF_FLAG if frame.extended else 0)
207  message_pad = bytes(frame.data) + b'\x00' * (8 - len(frame.data))
208  raw_message = struct.pack(self.FRAME_FORMAT, message_id, len(frame.data), message_pad)
209 
210  self.socket.send(raw_message)
211 
212  frame.ts_monotonic = time.monotonic()
213  frame.ts_real = time.time()
214  self._write_feedback_queue.put(frame)
215  except OSError as ex:
216  if ex.errno == errno.ENOBUFS:
217  time.sleep(0.0002)
218  else:
219  raise
220  else:
221  break
222  except Exception as ex:
223  self._write_feedback_queue.put(ex)
224 
226  try:
227  item = self._write_feedback_queue.get_nowait()
228  except queue.Empty:
229  return
230 
231  if isinstance(item, Exception):
232  raise item
233 
234  if isinstance(item, CANFrame):
235  self._tx_hook(item)
236  else:
237  raise DriverError('Unexpected item in write feedback queue: %r' % item)
238 
239  def close(self):
240  self._writer_thread_should_stop = True
241  self._writer_thread.join()
242  self.socket.close()
243 
244  def receive(self, timeout=None):
245  self._check_write_feedback()
246 
247  timeout = -1 if timeout is None else (timeout * 1000)
248 
249  if self._poll_rx.poll(timeout):
250  ts_real = None
251  ts_mono = None
252 
253  if NATIVE_SOCKETCAN:
254  # Reading the frame together with timestamps in the ancillary data structures
255  ancillary_len = 64 # Arbitrary value, must be large enough to accommodate all ancillary data
256  packet_raw, ancdata, _flags, _addr = self.socket.recvmsg(self.FRAME_SIZE,
257  socket.CMSG_SPACE(ancillary_len))
258 
259  # Parsing the timestamps
260  for cmsg_level, cmsg_type, cmsg_data in ancdata:
261  if cmsg_level == socket.SOL_SOCKET and cmsg_type == SO_TIMESTAMP:
262  sec, usec = struct.unpack(self.TIMEVAL_FORMAT, cmsg_data)
263  ts_real = sec + usec * 1e-6
264  else:
265  packet_raw = self.socket.recv(self.FRAME_SIZE)
266 
267  # Parsing the frame
268  can_id, can_dlc, can_data = struct.unpack(self.FRAME_FORMAT, packet_raw)
269 
270  # TODO: receive timestamps directly from hardware
271  # TODO: ...or at least obtain timestamps from the socket layer in local monotonic domain
272  if ts_real and not ts_mono:
273  ts_mono = self._convert_real_to_monotonic(ts_real)
274 
275  frame = CANFrame(can_id & CAN_EFF_MASK, can_data[0:can_dlc], bool(can_id & CAN_EFF_FLAG),
276  ts_monotonic=ts_mono, ts_real=ts_real)
277  self._rx_hook(frame)
278  return frame
279 
280  def send(self, message_id, message, extended=False):
281  self._check_write_feedback()
282  try:
283  self._write_queue.put_nowait(CANFrame(message_id, message, extended))
284  except queue.Full:
285  raise TxQueueFullError()
pyuavcan_v0.driver.socketcan.SocketCAN._poll_rx
_poll_rx
Definition: socketcan.py:165
pyuavcan_v0.driver.socketcan.can_frame
Definition: socketcan.py:89
pyuavcan_v0.driver.socketcan.CANSocket
Definition: socketcan.py:106
pyuavcan_v0.driver.socketcan.CANSocket.__init__
def __init__(self, fd)
Definition: socketcan.py:107
pyuavcan_v0.driver.socketcan.SocketCAN._writer_thread_loop
def _writer_thread_loop(self)
Definition: socketcan.py:196
pyuavcan_v0.driver.socketcan.SocketCAN.send
def send(self, message_id, message, extended=False)
Definition: socketcan.py:280
pyuavcan_v0.driver.common.AbstractDriver._rx_hook
def _rx_hook(self, frame)
Definition: driver/common.py:88
pyuavcan_v0.driver.socketcan.SocketCAN.__init__
def __init__(self, interface, **_extras)
Definition: socketcan.py:160
pyuavcan_v0.driver.socketcan.SocketCAN.close
def close(self)
Definition: socketcan.py:239
pyuavcan_v0.driver.socketcan.SocketCAN._check_write_feedback
def _check_write_feedback(self)
Definition: socketcan.py:225
pyuavcan_v0.driver.socketcan.SocketCAN._convert_real_to_monotonic
def _convert_real_to_monotonic(self, value)
Definition: socketcan.py:189
pyuavcan_v0.driver.common.AbstractDriver
Definition: driver/common.py:53
pyuavcan_v0.driver.socketcan.SocketCAN._write_queue
_write_queue
Definition: socketcan.py:169
pyuavcan_v0.driver.socketcan.CANSocket.close
def close(self)
Definition: socketcan.py:125
pyuavcan_v0.driver.socketcan.sockaddr_can
Definition: socketcan.py:70
pyuavcan_v0.driver.socketcan.SocketCAN._mono_to_real_estimator
_mono_to_real_estimator
Definition: socketcan.py:185
pyuavcan_v0.driver.socketcan.get_socket
def get_socket(ifname)
Definition: socketcan.py:39
pyuavcan_v0.driver.socketcan.SocketCAN._write_feedback_queue
_write_feedback_queue
Definition: socketcan.py:170
pyuavcan_v0.driver.socketcan.SocketCAN.socket
socket
Definition: socketcan.py:163
pyuavcan_v0.driver.common.CANFrame
Definition: driver/common.py:27
pyuavcan_v0.driver.socketcan.SocketCAN
Definition: socketcan.py:154
pyuavcan_v0.driver.socketcan.SocketCAN.FRAME_SIZE
int FRAME_SIZE
Definition: socketcan.py:156
pyuavcan_v0.driver.socketcan.CANSocket.fd
fd
Definition: socketcan.py:110
pyuavcan_v0.driver.socketcan.SocketCAN._writer_thread
_writer_thread
Definition: socketcan.py:172
pyuavcan_v0.driver.common.AbstractDriver._tx_hook
def _tx_hook(self, frame)
Definition: driver/common.py:85
pyuavcan_v0.driver.socketcan.CANSocket.recv
def recv(self, bufsize)
Definition: socketcan.py:112
pyuavcan_v0.driver.timestamp_estimator.TimestampEstimator
Definition: timestamp_estimator.py:82
pyuavcan_v0.driver.socketcan.SocketCAN.FRAME_FORMAT
string FRAME_FORMAT
Definition: socketcan.py:155
pyuavcan_v0.driver.socketcan.SocketCAN.receive
def receive(self, timeout=None)
Definition: socketcan.py:244
pyuavcan_v0.driver.socketcan.SocketCAN.TX_QUEUE_SIZE
int TX_QUEUE_SIZE
Definition: socketcan.py:158
pyuavcan_v0.driver.common.DriverError
Definition: driver/common.py:19
pyuavcan_v0.driver.socketcan.SocketCAN.TIMEVAL_FORMAT
string TIMEVAL_FORMAT
Definition: socketcan.py:157
pyuavcan_v0.driver.common.TxQueueFullError
Definition: driver/common.py:23
pyuavcan_v0.driver.socketcan.CANSocket.send
def send(self, data)
Definition: socketcan.py:117
pyuavcan_v0.driver.socketcan.SocketCAN._writer_thread_should_stop
_writer_thread_should_stop
Definition: socketcan.py:168
pyuavcan_v0.driver.socketcan.CANSocket.fileno
def fileno(self)
Definition: socketcan.py:122


uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:03