pyuavcan.transport.udp package

Module contents

UAVCAN/UDP transport overview

The UAVCAN/UDP transport is experimental and is not yet part of the UAVCAN specification. Future revisions may break wire compatibility until the transport is formally specified. Context: https://forum.uavcan.org/t/alternative-transport-protocols-in-uavcan/324/45?u=pavel.kirienko.

The UAVCAN/UDP transport is essentially a trivial stateless UDP blaster based on IP multicasting. This transport is intended for low-latency, high-throughput switched Ethernet networks with complex topologies. In the spirit of UAVCAN, it is designed to be simple and robust; much of the data handling work is offloaded to the standard underlying UDP/IP stack. Both IPv4 and IPv6 are supported by this design, although it is expected that the advantages of IPv6 over IPv4 are less relevant in an intravehicular setting.

The concept of anonymous transfer is not defined for UAVCAN/UDP; in this transport, in order to be able to emit a transfer, the node shall have a valid node-ID value. This means that an anonymous UAVCAN/UDP node can only listen to network traffic (i.e., can subscribe to subjects) but cannot transmit anything. If address auto-configuration is desired, lower-level solutions should be used, such as DHCP.

This transport module contains no media sublayers because the media abstraction is handled directly by the standard UDP/IP stack of the underlying operating system.

Per the UAVCAN transport model provided in the UAVCAN specification, the following transfer categories are supported:

Supported transfers

Unicast

Broadcast

Message

No

Yes

Service

Yes

Banned by Specification

Protocol definition

The entirety of the session specifier (pyuavcan.transport.SessionSpecifier) is reified through the standard UDP/IP stack without any special extensions. The transfer-ID, transfer priority, and the multi-frame transfer reassembly metadata are allocated in the UAVCAN-specific UDP datagram header.

Parameter

Manifested in

Transfer priority

UDP datagram payload (frame header)

Transfer-ID

Session specifier

Route specifier

16 least significant bits of the IP address

Data specifier

For message transfers: 16 least significant bits of the multicast group address. For service transfers: UDP destination port number.

There are two data types that model UAVCAN/UDP protocol data: UDPFrame and RawPacket. The latter is never used during normal operation but only during on-line capture sessions for reporting captured packets (see UDPCaptured).

IP address mapping

The IPv4 address of a node is structured as follows:

xxxxxxxx.xddddddd.nnnnnnnn.nnnnnnnn
\________/\_____/ \_______________/
 (9 bits) (7 bits)     (16 bits)
  prefix  subnet-ID     node-ID

Incoming traffic from IP addresses whose 16 most significant bits are different is rejected; this behavior enables co-existence of multiple independent UAVCAN/UDP networks along with other UDP protocols on the same network.

The subnet-ID is used to differentiate independent UAVCAN/UDP transport networks sharing the same IP network (e.g., multiple UAVCAN/UDP networks running on localhost or on some physical network). This is similar to the domain identifier in DDS. This value is not used anywhere else in the protocol other than in the construction of the multicast group address, as will be shown below.

Message transfers

Message transfers are executed as IP multicast transfers. The IPv4 multicast group address is computed statically as follows:

    fixed         reserved
   (9 bits)       (3 bits)
   ________          _
  /        \        / \
  11101111.0ddddddd.000sssss.ssssssss
  \__/      \_____/    \____________/
(4 bits)    (7 bits)      (13 bits)
  IPv4      subnet-ID     subject-ID
multicast   \_______________________/
 prefix             (23 bits)
            collision-free multicast
               addressing limit of
              Ethernet MAC for IPv4

From the most significant bit to the least significant bit, the IPv4 multicast group address components are as follows:

  • IPv4 multicast prefix is defined by RFC 1112.

  • The following 5 bits are set to 0b11110 by this Specification. The motivation is as follows:

    • Setting the four least significant bits of the most significant byte to 0b1111 moves the address range into the administratively-scoped range (239.0.0.0/8, RFC 2365), which ensures that there may be no conflicts with well-known multicast groups.

    • Setting the most significant bit of the second octet to zero ensures that there may be no conflict with reserved sub-ranges within the administratively-scoped range. The resulting range 239.0.0.0/9 is entirely ad-hoc defined.

    • Fixing the 5+4=9 most significant bits of the multicast group address ensures that the variability is confined to the 23 least significant bits of the address only, which is desirable because the IPv4 Ethernet MAC layer does not differentiate beyond the 23 least significant bits of the multicast group address (i.e., addresses that differ only in the 9 MSb collide at the MAC layer, which is unacceptable in a real-time system; see RFC 1112 section 6.4). Without this limitation, an engineer deploying a network might inadvertently create a configuration that causes MAC-layer collisions which may be difficult to detect.

  • The following 7 bits (the least significant bits of the second octet) are used to differentiate independent UAVCAN/UDP networks sharing the same physical IP network. Since the 9 most significant bits of the node IP address are not represented in the multicast group address, nodes whose IP addresses differ only by the 9 MSb are not distinguished by UAVCAN/UDP. This limitation does not appear to be significant, though, because such configurations are easy to avoid. It follows that there may be up to 128 independent UAVCAN/UDP networks sharing the same IP subnet.

  • The following 16 bits define the data specifier:

    • 3 bits reserved for future use.

    • 13 bits represent the subject-ID as-is.

Per RFC 1112, the default TTL is 1, which is unacceptable. Therefore, publishers should use the TTL value of 16 by default, which is chosen as a sensible default suitable for any intravehicular network.

Per RFC 1112, in order to emit a multicast packet, a limited level-1 implementation without the full support of IGMP and multicast-specific packet handling policies is sufficient.

Due to the dependency on the dynamic IGMP configuration, a newly configured subscriber may not immediately receive data from the subject – a brief subscription initialization latency may occur (typically it is well under one second). This is because the underlying IP stack needs to inform the network switch/router about its interest in a particular multicast group by sending an IGMP membership report first. A high-integrity application may choose to rely on a static switch configuration, in which case no initialization delay will take place.

Example:

Node IP address:    01111111 00000010 00000000 00001000
                         127        2        0        8

Subject-ID:                              00010 00101010

Multicast group:    11101111 00000010 00000010 00101010
                         239        2        2       42

Example:

Node IP address:    11000000 10101000 00000000 00000001
                         192      168        0        1

Subject-ID:                              00010 00101010

Multicast group:    11101111 00101000 00000010 00101010
                         239       40        2       42

Service transfers

Service transfers are executed as regular IP unicast transfers.

The service data specifier (pyuavcan.transport.ServiceDataSpecifier) is manifested on the wire as the destination UDP port number; the mapping function is implemented in udp_port_from_data_specifier(). The source port number can be arbitrary (ephemeral), its value is ignored.

UAVCAN uses a wide range of UDP ports. UDP/IP stacks that comply with the IANA ephemeral port range recommendations are expected to be compatible with this; otherwise, there may be port assignment conflicts. This, however, is not a problem for any major modern OS.

Datagram header format

Every UAVCAN/UDP frame contains the following header before the payload, encoded in the little-endian byte order, expressed here in the DSDL notation:

uint8 version           # =0 in this revision; ignore frame otherwise.
uint8 priority          # Like in CAN: 0 -- highest priority, 7 -- lowest priority.
void16                  # Set to zero when transmitting, ignore when receiving.
uint32 frame_index_eot  # MSB is set if the current frame is the last frame of the transfer.
uint64 transfer_id      # The transfer-ID never overflows.
void64                  # This space may be used later for runtime type identification.

The 31 least significant bits of the field frame_index_eot contain the frame index within the current transfer; the most significant bit (31st) is set if the current frame is the last frame of the transfer. Also see the documentation for UDPFrame.

Multi-frame transfers contain four bytes of CRC32-C (Castagnoli) at the end computed over the entire transfer payload. For more info on multi-frame transfers, please see pyuavcan.transport.commons.high_overhead_transport.TransferReassembler.

Unreliable networks and temporal redundancy

For unreliable networks, deterministic data loss mitigation is supported. This measure is only available for service transfers, not for message transfers due to their different semantics. If the probability of a frame loss exceeds the desired reliability threshold, the transport can be configured to repeat every outgoing service transfer a specified number of times, on the assumption that the probability of losing any given frame is uncorrelated (or weakly correlated) with that of its neighbors.

Assuming that the probability of transfer loss P is time-invariant, the influence of the multiplier M can be approximated as P' = P^M. For example, given a network that successfully delivers 99% of transfers, and the probabilities of adjacent transfer loss are uncorrelated, the multiplication factor of 2 can increase the link reliability up to 100% - (100% - 99%)^2 = 99.99%.

The duplicates are emitted immediately following the original transfer. For example, suppose that a service transfer contains three frames, F0 to F2, and the service transfer multiplication factor is two, then the resulting frame sequence would be as follows:

F0      F1      F2      F0      F1      F2
\_______________/       \_______________/
   main copy             redundant copy
 (TX timestamp)      (never TX-timestamped)

------------------ time ------------------>

As shown on the diagram, if the transmission timestamping is requested, only the first copy is timestamped. Further, any errors occurring during the transmission of redundant copies may be silently ignored by the stack, provided that the main copy is transmitted successfully.

The resulting behavior in the provided example is that the transport network may lose up to three unique frames without affecting the application. In the following example, the frames F0 and F2 of the main copy are lost, but the transfer survives:

F0 F1 F2 F0 F1 F2
|  |  |  |  |  |
x  |  x  |  |  \_____ F2 __________________________
   |     |  \________ F1 (redundant, discarded) x  \
   |     \___________ F0 ________________________  |
   \_________________ F1 ______________________  \ |
                                               \ | |
----- time ----->                              v v v
                                            reassembled
                                            multi-frame
                                             transfer

Removal of duplicate transfers at the opposite end of the link is natively guaranteed by the UAVCAN protocol; no special activities are needed there (read the UAVCAN Specification for background).

For time-deterministic (real-time) networks this strategy is preferred over the conventional confirmation-retry approach (e.g., the TCP model) because it results in more predictable network load, lower worst-case latency, and is stateless (participants do not make assumptions about the state of other agents involved in data exchange).

Implementation-specific details

Applications relying on this particular transport implementation will be unable to detect a node-ID conflict on the bus because the implementation discards all traffic originating from its own IP address. This is a very environment-specific edge case resulting from certain peculiarities of the Berkeley socket API. Other implementations of UAVCAN/UDP (particularly those for embedded systems) may not have this limitation.

Usage

Create two transport instances – one with a node-ID, one anonymous:

>>> import pyuavcan
>>> import pyuavcan.transport.udp
>>> tr_0 = pyuavcan.transport.udp.UDPTransport('127.9.1.42')
>>> tr_0.local_node_id                                             # Derived from the IP address: (1 << 8) + 42 = 298.
298
>>> tr_1 = pyuavcan.transport.udp.UDPTransport('127.9.15.254', local_node_id=None)  # Anonymous is only for listening.
>>> tr_1.local_node_id is None
True

Create an output and an input session:

>>> pm = pyuavcan.transport.PayloadMetadata(1024)
>>> ds = pyuavcan.transport.MessageDataSpecifier(111)
>>> pub = tr_0.get_output_session(pyuavcan.transport.OutputSessionSpecifier(ds, None), pm)
>>> pub.socket.getpeername()   # UDP port is fixed, and the multicast group address is computed as shown above.
('239.9.0.111', 16383)
>>> sub = tr_1.get_input_session(pyuavcan.transport.InputSessionSpecifier(ds, None), pm)

Send a transfer from one instance to the other:

>>> await_ = tr_1.loop.run_until_complete
>>> await_(pub.send(pyuavcan.transport.Transfer(pyuavcan.transport.Timestamp.now(),
...                                             pyuavcan.transport.Priority.LOW,
...                                             1111,
...                                             fragmented_payload=[]),
...                 tr_1.loop.time() + 1.0))
True
>>> await_(sub.receive(tr_1.loop.time() + 1.0))
TransferFrom(..., transfer_id=1111, ...)
>>> tr_0.close()
>>> tr_1.close()

Tooling

Run UAVCAN networks on the local loopback interface (127.x.y.z/8) or create virtual interfaces for testing.

Use Wireshark for monitoring and inspection.

Use netcat for trivial monitoring; e.g., listen to a UDP port like this: nc -ul 48469.

List all open UDP ports on the local machine: netstat -vpaun (GNU/Linux).

Inheritance diagram

Inheritance diagram of pyuavcan.transport.udp._udp, pyuavcan.transport.udp._frame, pyuavcan.transport.udp._session._input, pyuavcan.transport.udp._session._output, pyuavcan.transport.udp._socket_reader, pyuavcan.transport.udp._tracer

class pyuavcan.transport.udp.UDPTransport(local_ip_address: Union[str, ipaddress.IPv4Address, ipaddress.IPv6Address], local_node_id: Optional[int] = - 1, *, mtu: int = 1200, service_transfer_multiplier: int = 1, loop: Optional[asyncio.events.AbstractEventLoop] = None, anonymous: bool = False)[source]

Bases: pyuavcan.transport.Transport

The UAVCAN/UDP (IP v4/v6) transport is designed for low-latency, high-throughput, high-reliability vehicular networks based on Ethernet. Please read the module documentation for details.

TRANSFER_ID_MODULO = 18446744073709551616
VALID_MTU_RANGE = (1200, 9000)

The minimum is based on the IPv6 specification, which guarantees that the path MTU is at least 1280 bytes large. This value is also acceptable for virtually all IPv4 local or real-time networks. Lower MTU values shall not be used because they may lead to multi-frame transfer fragmentation where this is not expected by the designer, possibly violating the real-time constraints.

A conventional Ethernet jumbo frame can carry up to 9 KiB (9216 bytes). These are the application-level MTU values, so we take overheads into account.

VALID_SERVICE_TRANSFER_MULTIPLIER_RANGE = (1, 5)
__init__(local_ip_address: Union[str, ipaddress.IPv4Address, ipaddress.IPv6Address], local_node_id: Optional[int] = - 1, *, mtu: int = 1200, service_transfer_multiplier: int = 1, loop: Optional[asyncio.events.AbstractEventLoop] = None, anonymous: bool = False)[source]
Parameters
  • local_ip_address

    Specifies which local IP address to use for this transport. This setting also implicitly specifies the network interface to use. All output sockets will be bound (see bind()) to the specified local address. If the specified address is not available locally, the transport will fail with pyuavcan.transport.InvalidMediaConfigurationError.

    For use on the loopback interface, any IP address from the loopback range can be used; for example, 127.0.0.123. This generally does not work with physical interfaces; for example, if a host has one physical interface at 192.168.1.200, an attempt to run a node at 192.168.1.201 will trigger the media configuration error because bind() will fail with EADDRNOTAVAIL. One can change the node-ID of a physical transport by altering the network interface configuration in the underlying operating system itself.

    Using INADDR_ANY here (i.e., 0.0.0.0 for IPv4) is not expected to work reliably or be portable because this configuration is, generally, incompatible with multicast sockets (even in the anonymous mode). In order to set up even a listening multicast socket, it is necessary to specify the correct local address such that the underlying IP stack is aware of which interface to receive multicast packets from.

    When the anonymous mode is enabled, it is quite possible to snoop on the network even if there is another node running locally on the same interface (because sockets are initialized with SO_REUSEADDR and SO_REUSEPORT, when available).

  • local_node_id

    As explained previously, the node-ID is part of the IP address, but this parameter allows one to use the UDP transport in anonymous mode or easily build the node IP address from a subnet address (like 127.42.0.0) and a node-ID.

    • If the value is negative, the node-ID equals the 16 least significant bits of the local_ip_address. This is the default behavior.

    • If the value is None, an anonymous instance will be constructed, where the transport will reject any attempt to create an output session. The transport instance will also report its own local_node_id as None. The UAVCAN/UDP transport does not support anonymous transfers by design.

    • If the value is a non-negative integer, the 16 least significant bits of the local_ip_address are replaced with this value.

    Examples:

    local_ip_address

    local_node_id

    Local IP address

    Local node-ID

    127.42.1.200

    (default)

    127.42.1.200

    456 (from IP address)

    127.42.1.200

    42

    127.42.0.42

    42

    127.42.0.0

    42

    127.42.0.42

    42

    127.42.1.200

    None

    127.42.1.200

    anonymous

  • mtu

    The application-level MTU for outgoing packets. In other words, this is the maximum number of serialized bytes per UAVCAN/UDP frame. Transfers where the number of payload bytes does not exceed this value will be single-frame transfers, otherwise, multi-frame transfers will be used. This setting affects only outgoing frames; the MTU of incoming frames is fixed at a sufficiently large value to accept any meaningful UDP frame.

    The default value is the smallest valid value for reasons of compatibility.

  • service_transfer_multiplier – Deterministic data loss mitigation is disabled by default. This parameter specifies the number of times each outgoing service transfer will be repeated. This setting does not affect message transfers.

  • loop – The event loop to use. Defaults to asyncio.get_event_loop().

  • anonymous – DEPRECATED and scheduled for removal; replace with local_node_id=None.

property loop[source]
property protocol_parameters[source]
property local_node_id[source]
close()None[source]
get_input_session(specifier: pyuavcan.transport._session.InputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata)pyuavcan.transport.udp.UDPInputSession[source]
get_output_session(specifier: pyuavcan.transport._session.OutputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata)pyuavcan.transport.udp.UDPOutputSession[source]
sample_statistics()pyuavcan.transport.udp.UDPTransportStatistics[source]
property input_sessions[source]
property output_sessions[source]
property local_ip_address[source]
begin_capture(handler: Callable[[pyuavcan.transport._tracer.Capture], None])None[source]

Reported events are of type UDPCapture.

In order for the network capture to work, the local machine should be connected to a SPAN port of the switch. See https://en.wikipedia.org/wiki/Port_mirroring and read the documentation for your networking hardware. Additional preconditions must be met depending on the platform:

  • On GNU/Linux, network capture requires that either the process is executed by root, or the raw packet capture capability CAP_NET_RAW is enabled. For more info read man 7 capabilities and consider checking the docs for Wireshark/libpcap.

  • On Windows, Npcap needs to be installed and configured; see https://nmap.org/npcap/.

Packets that do not originate from the current UAVCAN/UDP subnet (configured on this transport instance) are not reported via this interface. This restriction is critical because there may be other UAVCAN/UDP networks running on the same physical L2 network segregated by different subnets, so that if foreign packets were not dropped, conflicts would occur.

property capture_active[source]
static make_tracer()pyuavcan.transport.udp.UDPTracer[source]

See UDPTracer.

async spoof(transfer: pyuavcan.transport._tracer.AlienTransfer, monotonic_deadline: float)bool[source]

Not implemented yet. Always raises NotImplementedError. When implemented, this method will rely on libpcap to emit spoofed link-layer packets.

class pyuavcan.transport.udp.UDPTransportStatistics(received_datagrams: Dict[pyuavcan.transport.DataSpecifier, pyuavcan.transport.udp.SocketReaderStatistics] = <factory>)[source]

Bases: pyuavcan.transport.TransportStatistics

received_datagrams: Dict[pyuavcan.transport._data_specifier.DataSpecifier, pyuavcan.transport.udp._socket_reader.SocketReaderStatistics]

Basic input session statistics: instances of SocketReaderStatistics keyed by data specifier.

__eq__(other)[source]
__hash__ = None
__init__(received_datagrams: Dict[pyuavcan.transport.DataSpecifier, pyuavcan.transport.udp.SocketReaderStatistics] = <factory>)None[source]
__repr__()[source]
class pyuavcan.transport.udp.UDPInputSession(specifier: pyuavcan.transport._session.InputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata, loop: asyncio.events.AbstractEventLoop, finalizer: Callable[], None])[source]

Bases: pyuavcan.transport.InputSession

As you already know, the UDP port number is a function of the data specifier. Hence, the input flow demultiplexing is mostly done by the UDP/IP stack implemented in the operating system itself, we just need to put a few basic abstractions on top. One of those abstractions is the internal socket reader class, which is not part of the API but its function is important if one needs to understand how the data flow is organized inside the library:

[Socket] 1   --->   1 [Demultiplexer] 1   --->   * [Input session] 1   --->   1 [API]

(The plurality notation is supposed to resemble UML: 1 - one, * - many.)

A UDP datagram is an atomic unit of workload for the stack. Unlike, say, the serial transport, the operating system does the low-level work of framing and CRC checking for us (thank you), so we get our stuff sorted up to the OSI layer 4 inclusive. The processing pipeline per datagram is as follows:

  • The socket reader obtains the datagram from the socket using recvfrom(). The source IP address is mapped to a node-ID and the contents are parsed into a UAVCAN UDP frame instance. If anything goes wrong here (like if the source IP address belongs to a wrong subnet or the datagram does not contain a valid UAVCAN frame or whatever), the datagram is dropped and the appropriate statistical counters are updated.

  • The socket reader looks up the input session instances that have subscribed for the datagram from the current source node-ID (derived from the IP address) and passes the frame to them. By the way, remember that this is a zero-copy stack, so every subscribed input session gets a reference to the same instance of the frame, although it is beside the point right now.

  • Upon reception of the frame, the input session (one of many) updates its reassembler state machine and runs all that meticulous bookkeeping you can’t get away from if you need to receive multi-frame transfers.

  • If the received frame happened to complete a transfer, the input session passes it up to the higher layer.

Now, an attentive reader might exclaim:

But look! If there is more than one input session instance per source node-ID, we’d be running multiple transfer reassemblers with the same input data, which is inefficient! Why can’t we extract the task of transfer reassembly into the socket reader, before the pipeline is forked, to avoid the extra workload?

That is a good question, and here’s why:

  • The most important reason is that the proposal would only work if the state of a transfer reassembler was a function of the input frame flow only. This is not the case. The state of a transfer reassembler is also defined by its configuration parameters which are defined per-instance, which in turn are defined per input session instance. In particular, the transfer-ID timeout is configured separately per input session.

  • The case where there is more than one input session per remote node-ID is uncommon. In fact, it may only occur if the higher layers requested a promiscuous and a selective session at the same time, which normally does not happen with UAVCAN. We support this use case nevertheless because this library is supposed to offer a generic and flexible API due to its intended usages (read the library design goals).

  • The computing load of updating the state machine of a transfer reassembler is minuscule. The most intensive computation happening there is the CRC update, which is not intense at all.

The architecture of the data processing pipeline in PyUAVCAN is complex, but that is due to the high-level requirements for the library: it has to support all transport protocols, a lot of media layers, and be portable, so trade-offs had to be made. It should be understood that actual safety-critical implementations used in production systems can be far simpler because generally they do not have to be multi-transport and multi-platform.

DEFAULT_TRANSFER_ID_TIMEOUT = 2.0

Units are seconds. Can be overridden after instantiation if needed.

__init__(specifier: pyuavcan.transport._session.InputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata, loop: asyncio.events.AbstractEventLoop, finalizer: Callable[], None])[source]
async receive(monotonic_deadline: float)Optional[pyuavcan.transport._transfer.TransferFrom][source]
property transfer_id_timeout[source]
property specifier[source]
property payload_metadata[source]
close()None[source]
class pyuavcan.transport.udp.PromiscuousUDPInputSession(specifier: pyuavcan.transport._session.InputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata, loop: asyncio.events.AbstractEventLoop, finalizer: Callable[], None])[source]

Bases: pyuavcan.transport.udp.UDPInputSession

__init__(specifier: pyuavcan.transport._session.InputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata, loop: asyncio.events.AbstractEventLoop, finalizer: Callable[], None])[source]

Do not call this directly, use the factory method instead.

sample_statistics()pyuavcan.transport.udp.PromiscuousUDPInputSessionStatistics[source]
class pyuavcan.transport.udp.SelectiveUDPInputSession(specifier: pyuavcan.transport._session.InputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata, loop: asyncio.events.AbstractEventLoop, finalizer: Callable[], None])[source]

Bases: pyuavcan.transport.udp.UDPInputSession

__init__(specifier: pyuavcan.transport._session.InputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata, loop: asyncio.events.AbstractEventLoop, finalizer: Callable[], None])[source]

Do not call this directly, use the factory method instead.

sample_statistics()pyuavcan.transport.udp.SelectiveUDPInputSessionStatistics[source]
class pyuavcan.transport.udp.UDPInputSessionStatistics(transfers: int = 0, frames: int = 0, payload_bytes: int = 0, errors: int = 0, drops: int = 0)[source]

Bases: pyuavcan.transport.SessionStatistics

class pyuavcan.transport.udp.PromiscuousUDPInputSessionStatistics(transfers: 'int' = 0, frames: 'int' = 0, payload_bytes: 'int' = 0, errors: 'int' = 0, drops: 'int' = 0, reassembly_errors_per_source_node_id: 'typing.Dict[int, typing.Dict[TransferReassembler.Error, int]]' = <factory>)[source]

Bases: pyuavcan.transport.udp.UDPInputSessionStatistics

reassembly_errors_per_source_node_id: Dict[int, Dict[pyuavcan.transport.commons.high_overhead_transport._transfer_reassembler.TransferReassembler.Error, int]]

Keys are source node-IDs; values are dicts where keys are error enum members and values are counts.

__eq__(other)[source]
__hash__ = None
__init__(transfers: int = 0, frames: int = 0, payload_bytes: int = 0, errors: int = 0, drops: int = 0, reassembly_errors_per_source_node_id: Dict[int, Dict[pyuavcan.transport.commons.high_overhead_transport.TransferReassembler.Error, int]] = <factory>)None[source]
__repr__()[source]
class pyuavcan.transport.udp.SelectiveUDPInputSessionStatistics(transfers: 'int' = 0, frames: 'int' = 0, payload_bytes: 'int' = 0, errors: 'int' = 0, drops: 'int' = 0, reassembly_errors: 'typing.Dict[TransferReassembler.Error, int]' = <factory>)[source]

Bases: pyuavcan.transport.udp.UDPInputSessionStatistics

reassembly_errors: Dict[pyuavcan.transport.commons.high_overhead_transport._transfer_reassembler.TransferReassembler.Error, int]

Keys are error enum members and values are counts.

__eq__(other)[source]
__hash__ = None
__init__(transfers: int = 0, frames: int = 0, payload_bytes: int = 0, errors: int = 0, drops: int = 0, reassembly_errors: Dict[pyuavcan.transport.commons.high_overhead_transport.TransferReassembler.Error, int] = <factory>)None[source]
__repr__()[source]
class pyuavcan.transport.udp.UDPOutputSession(specifier: pyuavcan.transport._session.OutputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata, mtu: int, multiplier: int, sock: socket.socket, loop: asyncio.events.AbstractEventLoop, finalizer: Callable[], None])[source]

Bases: pyuavcan.transport.OutputSession

The output session logic is extremely simple because most of the work is handled by the UDP/IP stack of the operating system. Here we just split the transfer into frames, encode the frames, and write them into the socket one by one. If the transfer multiplier is greater than one (for unreliable networks), we repeat that the required number of times.

__init__(specifier: pyuavcan.transport._session.OutputSessionSpecifier, payload_metadata: pyuavcan.transport._payload_metadata.PayloadMetadata, mtu: int, multiplier: int, sock: socket.socket, loop: asyncio.events.AbstractEventLoop, finalizer: Callable[], None])[source]

Do not call this directly. Instead, use the factory method. Instances take ownership of the socket.

async send(transfer: pyuavcan.transport._transfer.Transfer, monotonic_deadline: float)bool[source]
enable_feedback(handler: Callable[[pyuavcan.transport._session.Feedback], None])None[source]
disable_feedback()None[source]
property specifier[source]
property payload_metadata[source]
sample_statistics()pyuavcan.transport.SessionStatistics[source]
close()None[source]
property socket[source]

Provides access to the underlying UDP socket.

class pyuavcan.transport.udp.UDPFeedback(original_transfer_timestamp: pyuavcan.transport._timestamp.Timestamp, first_frame_transmission_timestamp: pyuavcan.transport._timestamp.Timestamp)[source]

Bases: pyuavcan.transport.Feedback

__init__(original_transfer_timestamp: pyuavcan.transport._timestamp.Timestamp, first_frame_transmission_timestamp: pyuavcan.transport._timestamp.Timestamp)[source]
property original_transfer_timestamp[source]
property first_frame_transmission_timestamp[source]
class pyuavcan.transport.udp.UDPFrame(priority: pyuavcan.transport._transfer.Priority, transfer_id: int, index: int, end_of_transfer: bool, payload: memoryview)[source]

Bases: pyuavcan.transport.commons.high_overhead_transport.Frame

The header format is up to debate until it’s frozen in Specification.

An important thing to keep in mind is that the minimum size of an UDP/IPv4 payload when transferred over 100M Ethernet is 18 bytes, due to the minimum Ethernet frame size limit. That is, if the application payload requires less space, the missing bytes will be padded out to the minimum size.

The current header format enables encoding by trivial memory aliasing on any conventional little-endian platform:

struct Header {
    uint8_t  version;
    uint8_t  priority;
    uint16_t _reserved_a;   // Set to zero when encoding, ignore when decoding.
    uint32_t frame_index_eot;
    uint64_t transfer_id;
    uint64_t _reserved_b;   // Set to zero when encoding, ignore when decoding.
};
static_assert(sizeof(struct Header) == 24, "Invalid layout");

If you have any feedback concerning the frame format, please bring it to https://forum.uavcan.org/t/alternative-transport-protocols/324.

MAC header

IP header

UDP header

UAVCAN header

UAVCAN payload

Layers modeled by this type

TRANSFER_ID_MASK = 18446744073709551615
INDEX_MASK = 2147483647
compile_header_and_payload()Tuple[memoryview, memoryview][source]

Compiles the UDP frame header and returns it as a read-only memoryview along with the payload, separately. The caller is supposed to handle the header and the payload independently. The reason is to avoid unnecessary data copying in the user space, allowing the caller to rely on the vectorized IO API instead (sendmsg).

static parse(image: memoryview)Optional[pyuavcan.transport.udp._frame.UDPFrame][source]
__delattr__(name)[source]
__eq__(other)[source]
__hash__()[source]
__init__(priority: pyuavcan.transport._transfer.Priority, transfer_id: int, index: int, end_of_transfer: bool, payload: memoryview)None[source]
__setattr__(name, value)[source]
priority: pyuavcan.transport._transfer.Priority

Transfer priority should be the same for all frames within the transfer.

transfer_id: int

Transfer-ID is incremented whenever a transfer under a specific session-specifier is emitted. Always non-negative.

index: int

Index of the frame within its transfer, starting from zero. Always non-negative.

end_of_transfer: bool

True for the last frame within the transfer.

payload: memoryview

The data carried by the frame. Multi-frame transfer payload is suffixed with its CRC32C. May be empty.

pyuavcan.transport.udp.node_id_to_unicast_ip(local_ip_address: Union[ipaddress.IPv4Address, ipaddress.IPv6Address], node_id: int)Union[ipaddress.IPv4Address, ipaddress.IPv6Address][source]

The local IP address is needed to deduce the subnet that the UAVCAN/UDP transport is operating on. The function simply combines the most significant bits from the first argument with the second argument.

>>> from ipaddress import ip_address
>>> str(node_id_to_unicast_ip(ip_address('127.42.11.22'), 123))
'127.42.0.123'
>>> str(node_id_to_unicast_ip(ip_address('127.42.11.22'), 456))
'127.42.1.200'
>>> str(node_id_to_unicast_ip(ip_address('239.42.11.22'), 456))
Traceback (most recent call last):
  ...
ValueError: The local address shall be a unicast address, not multicast: 239.42.11.22
>>> str(node_id_to_unicast_ip(ip_address('127.42.11.22'), 65536))
Traceback (most recent call last):
  ...
ValueError: Invalid node-ID...
pyuavcan.transport.udp.unicast_ip_to_node_id(local_ip_address: Union[ipaddress.IPv4Address, ipaddress.IPv6Address], node_ip_address: Union[ipaddress.IPv4Address, ipaddress.IPv6Address])Optional[int][source]

Returns the node-ID if the node IP address and the local IP address belong to the same subnet. Returns None if the node is not a member of the local subnet. Raises a value error if either address is a multicast group address.

>>> from ipaddress import ip_address
>>> unicast_ip_to_node_id(ip_address('127.42.1.1'), ip_address('127.42.1.200'))
456
>>> unicast_ip_to_node_id(ip_address('127.0.0.99'), ip_address('127.0.0.99'))
99
>>> unicast_ip_to_node_id(ip_address('127.99.1.1'), ip_address('127.42.1.200'))  # Returns None
>>> unicast_ip_to_node_id(ip_address('239.42.1.1'), ip_address('127.42.1.200'))
Traceback (most recent call last):
  ...
ValueError: Multicast group address cannot be a local IP address...
>>> unicast_ip_to_node_id(ip_address('127.42.1.1'), ip_address('239.42.1.200'))
Traceback (most recent call last):
  ...
ValueError: Multicast group address cannot be mapped to a node-ID...
pyuavcan.transport.udp.message_data_specifier_to_multicast_group(local_ip_address: Union[ipaddress.IPv4Address, ipaddress.IPv6Address], data_specifier: pyuavcan.transport._data_specifier.MessageDataSpecifier)Union[ipaddress.IPv4Address, ipaddress.IPv6Address][source]

The local IP address is needed to deduce the subnet that the UAVCAN/UDP transport is operating on. For IPv4, the resulting address is constructed as follows:

11101111.0ddddddd.ssssssss.ssssssss
          \_____/ \_______________/
         subnet-ID    subject-ID

Where the subnet-ID is taken from the local IP address:

xxxxxxxx.xddddddd.nnnnnnnn.nnnnnnnn
          \_____/
         subnet-ID
>>> from pyuavcan.transport import MessageDataSpecifier
>>> from ipaddress import ip_address
>>> str(message_data_specifier_to_multicast_group(ip_address('127.42.11.22'), MessageDataSpecifier(123)))
'239.42.0.123'
>>> str(message_data_specifier_to_multicast_group(ip_address('192.168.11.22'), MessageDataSpecifier(456)))
'239.40.1.200'
>>> str(message_data_specifier_to_multicast_group(ip_address('239.168.11.22'), MessageDataSpecifier(456)))
Traceback (most recent call last):
  ...
ValueError: The local address shall be a unicast address, not multicast: 239.168.11.22
pyuavcan.transport.udp.multicast_group_to_message_data_specifier(local_ip_address: Union[ipaddress.IPv4Address, ipaddress.IPv6Address], multicast_group: Union[ipaddress.IPv4Address, ipaddress.IPv6Address])Optional[pyuavcan.transport._data_specifier.MessageDataSpecifier][source]

The inverse of message_data_specifier_to_multicast_group(). The local IP address is needed to ensure that the multicast group belongs to the correct UAVCAN/UDP subnet. The return value is None if the multicast group is not valid per the current UAVCAN/UDP specification or if it belongs to a different UAVCAN/UDP subnet.

>>> from ipaddress import ip_address
>>> multicast_group_to_message_data_specifier(ip_address('127.42.11.22'), ip_address('239.42.1.200'))
MessageDataSpecifier(subject_id=456)
>>> multicast_group_to_message_data_specifier(ip_address('127.42.11.22'), ip_address('239.43.1.200'))    # -> None
>>> multicast_group_to_message_data_specifier(ip_address('127.42.11.22'), ip_address('239.42.255.200'))  # -> None
pyuavcan.transport.udp.service_data_specifier_to_udp_port(ds: pyuavcan.transport._data_specifier.ServiceDataSpecifier)int[source]

For request transfers, the destination port is computed as SERVICE_BASE_PORT plus service-ID multiplied by two. For response transfers, it is as above plus one.

>>> service_data_specifier_to_udp_port(ServiceDataSpecifier(0, ServiceDataSpecifier.Role.REQUEST))
16384
>>> service_data_specifier_to_udp_port(ServiceDataSpecifier(0, ServiceDataSpecifier.Role.RESPONSE))
16385
>>> service_data_specifier_to_udp_port(ServiceDataSpecifier(511, ServiceDataSpecifier.Role.REQUEST))
17406
>>> service_data_specifier_to_udp_port(ServiceDataSpecifier(511, ServiceDataSpecifier.Role.RESPONSE))
17407
pyuavcan.transport.udp.udp_port_to_service_data_specifier(port: int)Optional[pyuavcan.transport._data_specifier.ServiceDataSpecifier][source]

The inverse of service_data_specifier_to_udp_port(). Returns None for invalid ports.

>>> udp_port_to_service_data_specifier(16384)
ServiceDataSpecifier(service_id=0, role=...REQUEST...)
>>> udp_port_to_service_data_specifier(16385)
ServiceDataSpecifier(service_id=0, role=...RESPONSE...)
>>> udp_port_to_service_data_specifier(17406)
ServiceDataSpecifier(service_id=511, role=...REQUEST...)
>>> udp_port_to_service_data_specifier(17407)
ServiceDataSpecifier(service_id=511, role=...RESPONSE...)
>>> udp_port_to_service_data_specifier(50000)  # Returns None
>>> udp_port_to_service_data_specifier(10000)  # Returns None
class pyuavcan.transport.udp.LinkLayerPacket(protocol: socket.AddressFamily, source: memoryview, destination: memoryview, payload: memoryview)[source]

Bases: object

OSI L2 packet representation. The addresses are represented here in the link-native byte order (big endian for Ethernet).

protocol: socket.AddressFamily

The protocol encapsulated inside this link-layer packet; e.g., IPv6.

source: memoryview
destination: memoryview

Link-layer addresses, if applicable. Empty if not supported by the link layer.

payload: memoryview

The packet of the specified protocol.

__repr__()str[source]

The repr displays only the first 100 bytes of the payload. If the payload is longer, its string representation is appended with an ellipsis.

__delattr__(name)[source]
__eq__(other)[source]
__hash__()[source]
__init__(protocol: socket.AddressFamily, source: memoryview, destination: memoryview, payload: memoryview)None[source]
__setattr__(name, value)[source]
class pyuavcan.transport.udp.IPPacket(protocol: ‘int’, payload: ‘memoryview’)[source]

Bases: object

protocol: int
payload: memoryview
property source_destination[source]
static parse(link_layer_packet: pyuavcan.transport.udp._ip._link_layer.LinkLayerPacket)Optional[pyuavcan.transport.udp._tracer.IPPacket][source]
__delattr__(name)[source]
__eq__(other)[source]
__hash__()[source]
__init__(protocol: int, payload: memoryview)None[source]
__repr__()[source]
__setattr__(name, value)[source]
class pyuavcan.transport.udp.IPv4Packet(protocol: ‘int’, payload: ‘memoryview’, source: ‘IPv4Address’, destination: ‘IPv4Address’)[source]

Bases: pyuavcan.transport.udp.IPPacket

source: ipaddress.IPv4Address
destination: ipaddress.IPv4Address
property source_destination[source]
static parse_payload(link_layer_payload: memoryview)Optional[pyuavcan.transport.udp._tracer.IPv4Packet][source]
__delattr__(name)[source]
__eq__(other)[source]
__hash__()[source]
__init__(protocol: int, payload: memoryview, source: ipaddress.IPv4Address, destination: ipaddress.IPv4Address)None[source]
__repr__()[source]
__setattr__(name, value)[source]
class pyuavcan.transport.udp.IPv6Packet(protocol: ‘int’, payload: ‘memoryview’, source: ‘IPv6Address’, destination: ‘IPv6Address’)[source]

Bases: pyuavcan.transport.udp.IPPacket

source: ipaddress.IPv6Address
destination: ipaddress.IPv6Address
property source_destination[source]
static parse_payload(link_layer_payload: memoryview)Optional[pyuavcan.transport.udp._tracer.IPv6Packet][source]
__delattr__(name)[source]
__eq__(other)[source]
__hash__()[source]
__init__(protocol: int, payload: memoryview, source: ipaddress.IPv6Address, destination: ipaddress.IPv6Address)None[source]
__repr__()[source]
__setattr__(name, value)[source]
class pyuavcan.transport.udp.UDPIPPacket(source_port: ‘int’, destination_port: ‘int’, payload: ‘memoryview’)[source]

Bases: object

source_port: int
destination_port: int
payload: memoryview
static parse(ip_packet: pyuavcan.transport.udp._tracer.IPPacket)Optional[pyuavcan.transport.udp._tracer.UDPIPPacket][source]
__delattr__(name)[source]
__eq__(other)[source]
__hash__()[source]
__init__(source_port: int, destination_port: int, payload: memoryview)None[source]
__repr__()[source]
__setattr__(name, value)[source]
class pyuavcan.transport.udp.UDPCapture(timestamp: pyuavcan.transport._timestamp.Timestamp, link_layer_packet: pyuavcan.transport.udp._ip._link_layer.LinkLayerPacket)[source]

Bases: pyuavcan.transport.Capture

The UDP transport does not differentiate between sent and received packets. See pyuavcan.transport.udp.UDPTransport.begin_capture() for details.

parse()Optional[Tuple[pyuavcan.transport._tracer.AlienSessionSpecifier, pyuavcan.transport.udp._frame.UDPFrame]][source]

The parsed representation is only defined if the packet is a valid UAVCAN/UDP frame. The source node-ID is never None.

static get_transport_type()Type[pyuavcan.transport.udp._udp.UDPTransport][source]
__delattr__(name)[source]
__eq__(other)[source]
__hash__()[source]
__init__(timestamp: pyuavcan.transport._timestamp.Timestamp, link_layer_packet: pyuavcan.transport.udp._ip._link_layer.LinkLayerPacket)None[source]
__repr__()[source]
__setattr__(name, value)[source]
class pyuavcan.transport.udp.UDPTracer[source]

Bases: pyuavcan.transport.Tracer

This is like a Wireshark dissector but UAVCAN-focused. Return types from update():

__init__()None[source]
update(cap: pyuavcan.transport._tracer.Capture)Optional[pyuavcan.transport._tracer.Trace][source]
class pyuavcan.transport.udp.UDPErrorTrace(timestamp: ‘pyuavcan.transport.Timestamp’, error: ‘TransferReassembler.Error’)[source]

Bases: pyuavcan.transport.ErrorTrace

error: pyuavcan.transport.commons.high_overhead_transport._transfer_reassembler.TransferReassembler.Error
__delattr__(name)[source]
__eq__(other)[source]
__hash__()[source]
__init__(timestamp: pyuavcan.transport._timestamp.Timestamp, error: pyuavcan.transport.commons.high_overhead_transport._transfer_reassembler.TransferReassembler.Error)None[source]
__repr__()[source]
__setattr__(name, value)[source]