Demo

This section demonstrates how to build UAVCAN applications using PyUAVCAN. It has been tested against GNU/Linux and Windows; it is also expected to work with any other major OS. The document is arranged as follows:

  • In the first section we introduce a couple of custom data types to illustrate how they can be dealt with.

  • The second section shows a simple demo node that implements a temperature controller and provides a custom RPC-service.

  • The third section provides a hands-on illustration of the data distribution functionality of UAVCAN with the help of Yakut — a command-line utility for diagnostics and debugging of UAVCAN networks.

  • The fourth section adds a second node that simulates the plant whose temperature is controlled by the first one.

  • The last section explains how to perform orchestration and configuration management of UAVCAN networks.

You are expected to be familiar with terms like UAVCAN node, DSDL, subject-ID, RPC-service. If not, skim through the UAVCAN Guide first.

If you want to follow along, install PyUAVCAN and switch to a new directory before continuing.

DSDL definitions

Every UAVCAN application depends on the standard DSDL definitions located in the namespace uavcan. The standard namespace is part of the regulated namespaces maintained by the UAVCAN project. Grab your copy from git:

git clone https://github.com/UAVCAN/public_regulated_data_types

The demo relies on two vendor-specific data types located in the root namespace sirius_cyber_corp. The root namespace directory layout is as follows:

sirius_cyber_corp/                              # root namespace directory
    PerformLinearLeastSquaresFit.1.0.uavcan     # service type definition
    PointXY.1.0.uavcan                          # nested message type definition

Type sirius_cyber_corp.PerformLinearLeastSquaresFit.1.0, file sirius_cyber_corp/PerformLinearLeastSquaresFit.1.0.uavcan:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
# This service accepts a list of 2D point coordinates and returns the best-fit linear function coefficients.
# If no solution exists, the returned coefficients are NaN.

PointXY.1.0[<64] points

@extent 1024 * 8

---

float64 slope
float64 y_intercept

@extent 64 * 8

Type sirius_cyber_corp.PointXY.1.0, file sirius_cyber_corp/PointXY.1.0.uavcan:

1
2
3
float16 x
float16 y
@sealed

First node

Copy-paste the source code given below into a file named demo_app.py. For the sake of clarity, move the custom DSDL root namespace directory sirius_cyber_corp/ that we created above into custom_data_types/. You should end up with the following directory structure:

custom_data_types/
    sirius_cyber_corp/                          # Created in the previous section
        PerformLinearLeastSquaresFit.1.0.uavcan
        PointXY.1.0.uavcan
public_regulated_data_types/                    # Clone from git
    uavcan/                                     # The standard DSDL namespace
        ...
    ...
demo_app.py                                     # The thermostat node script

Here comes demo_app.py:

  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
#!/usr/bin/env python3
# Distributed under CC0 1.0 Universal (CC0 1.0) Public Domain Dedication.
# pylint: disable=ungrouped-imports,wrong-import-position

import os
import sys
import pathlib
import asyncio
import logging
import importlib
import pyuavcan

# Production applications are recommended to compile their DSDL namespaces as part of the build process. The enclosed
# file "setup.py" provides an example of how to do that. The output path we specify here shall match that of "setup.py".
# Here we compile DSDL just-in-time to demonstrate an alternative.
compiled_dsdl_dir = pathlib.Path(__file__).resolve().parent / ".demo_dsdl_compiled"

# Make the compilation outputs importable. Let your IDE index this directory as sources to enable code completion.
sys.path.insert(0, str(compiled_dsdl_dir))

try:
    import sirius_cyber_corp  # This is our vendor-specific root namespace. Custom data types.
    import pyuavcan.application  # This module requires the root namespace "uavcan" to be transcompiled.
except (ImportError, AttributeError):  # Redistributable applications typically don't need this section.
    logging.warning("Transcompiling DSDL, this may take a while")
    src_dir = pathlib.Path(__file__).resolve().parent
    pyuavcan.dsdl.compile_all(
        [
            src_dir / "custom_data_types/sirius_cyber_corp",
            src_dir / "public_regulated_data_types/uavcan/",
        ],
        output_directory=compiled_dsdl_dir,
    )
    importlib.invalidate_caches()  # Python runtime requires this.
    import sirius_cyber_corp
    import pyuavcan.application

# Import other namespaces we're planning to use. Nested namespaces are not auto-imported, so in order to reach,
# say, "uavcan.node.Heartbeat", you have to "import uavcan.node".
import uavcan.node  # noqa
import uavcan.si.sample.temperature  # noqa
import uavcan.si.unit.temperature  # noqa
import uavcan.si.unit.voltage  # noqa


class DemoApp:
    REGISTER_FILE = "demo_app.db"
    """
    The register file stores configuration parameters of the local application/node. The registers can be modified
    at launch via environment variables and at runtime via RPC-service "uavcan.register.Access".
    The file will be created automatically if it doesn't exist.
    """

    def __init__(self) -> None:
        node_info = uavcan.node.GetInfo_1_0.Response(
            software_version=uavcan.node.Version_1_0(major=1, minor=0),
            name="org.uavcan.pyuavcan.demo.demo_app",
        )
        # The Node class is basically the central part of the library -- it is the bridge between the application and
        # the UAVCAN network. Also, it implements certain standard application-layer functions, such as publishing
        # heartbeats and port introspection messages, responding to GetInfo, serving the register API, etc.
        # The register file stores the configuration parameters of our node (you can inspect it using SQLite Browser).
        self._node = pyuavcan.application.make_node(node_info, DemoApp.REGISTER_FILE)

        # Published heartbeat fields can be configured as follows.
        self._node.heartbeat_publisher.mode = uavcan.node.Mode_1_0.OPERATIONAL  # type: ignore
        self._node.heartbeat_publisher.vendor_specific_status_code = os.getpid() % 100

        # Now we can create ports to interact with the network.
        # They can also be created or destroyed later at any point after initialization.
        # A port is created by specifying its data type and its name (similar to topic names in ROS or DDS).
        # The subject-ID is obtained from the standard register named "uavcan.sub.temperature_setpoint.id".
        # It can also be modified via environment variable "UAVCAN__SUB__TEMPERATURE_SETPOINT__ID".
        self._sub_t_sp = self._node.make_subscriber(uavcan.si.unit.temperature.Scalar_1_0, "temperature_setpoint")

        # As you may probably guess by looking at the port names, we are building a basic thermostat here.
        # We subscribe to the temperature setpoint, temperature measurement (process variable), and publish voltage.
        # The corresponding registers are "uavcan.sub.temperature_measurement.id" and "uavcan.pub.heater_voltage.id".
        self._sub_t_pv = self._node.make_subscriber(uavcan.si.sample.temperature.Scalar_1_0, "temperature_measurement")
        self._pub_v_cmd = self._node.make_publisher(uavcan.si.unit.voltage.Scalar_1_0, "heater_voltage")

        # Create an RPC-server. The service-ID is read from standard register "uavcan.srv.least_squares.id".
        # This service is optional: if the service-ID is not specified, we simply don't provide it.
        try:
            srv_least_sq = self._node.get_server(sirius_cyber_corp.PerformLinearLeastSquaresFit_1_0, "least_squares")
            srv_least_sq.serve_in_background(self._serve_linear_least_squares)
        except pyuavcan.application.register.MissingRegisterError:
            logging.info("The least squares service is disabled by configuration")

        # Create another RPC-server using a standard service type for which a fixed service-ID is defined.
        # We don't specify the port name so the service-ID defaults to the fixed port-ID.
        # We could, of course, use it with a different service-ID as well, if needed.
        self._node.get_server(uavcan.node.ExecuteCommand_1_1).serve_in_background(self._serve_execute_command)

        self._node.start()  # Don't forget to start the node!

    @staticmethod
    async def _serve_linear_least_squares(
        request: sirius_cyber_corp.PerformLinearLeastSquaresFit_1_0.Request,
        metadata: pyuavcan.presentation.ServiceRequestMetadata,
    ) -> sirius_cyber_corp.PerformLinearLeastSquaresFit_1_0.Response:
        logging.info("Least squares request %s from node %d", request, metadata.client_node_id)
        sum_x = sum(map(lambda p: p.x, request.points))  # type: ignore
        sum_y = sum(map(lambda p: p.y, request.points))  # type: ignore
        a = sum_x * sum_y - len(request.points) * sum(map(lambda p: p.x * p.y, request.points))  # type: ignore
        b = sum_x * sum_x - len(request.points) * sum(map(lambda p: p.x ** 2, request.points))  # type: ignore
        try:
            slope = a / b
            y_intercept = (sum_y - slope * sum_x) / len(request.points)
        except ZeroDivisionError:
            slope = float("nan")
            y_intercept = float("nan")
        return sirius_cyber_corp.PerformLinearLeastSquaresFit_1_0.Response(slope=slope, y_intercept=y_intercept)

    @staticmethod
    async def _serve_execute_command(
        request: uavcan.node.ExecuteCommand_1_1.Request,
        metadata: pyuavcan.presentation.ServiceRequestMetadata,
    ) -> uavcan.node.ExecuteCommand_1_1.Response:
        logging.info("Execute command request %s from node %d", request, metadata.client_node_id)
        if request.command == uavcan.node.ExecuteCommand_1_1.Request.COMMAND_FACTORY_RESET:
            try:
                os.unlink(DemoApp.REGISTER_FILE)  # Reset to defaults by removing the register file.
            except OSError:  # Do nothing if already removed.
                pass
            return uavcan.node.ExecuteCommand_1_1.Response(uavcan.node.ExecuteCommand_1_1.Response.STATUS_SUCCESS)
        return uavcan.node.ExecuteCommand_1_1.Response(uavcan.node.ExecuteCommand_1_1.Response.STATUS_BAD_COMMAND)

    async def run(self) -> None:
        """
        The main method that runs the business logic. It is also possible to use the library in an IoC-style
        by using receive_in_background() for all subscriptions if desired.
        """
        temperature_setpoint = 0.0
        temperature_error = 0.0

        async def on_setpoint(msg: uavcan.si.unit.temperature.Scalar_1_0, _: pyuavcan.transport.TransferFrom) -> None:
            nonlocal temperature_setpoint
            temperature_setpoint = msg.kelvin

        self._sub_t_sp.receive_in_background(on_setpoint)  # IoC-style handler.

        # Expose internal states to external observers for diagnostic purposes. Here, we define read-only registers.
        # Since they are computed at every invocation, they are never stored in the register file.
        self._node.registry["thermostat.error"] = lambda: temperature_error
        self._node.registry["thermostat.setpoint"] = lambda: temperature_setpoint

        # Read application settings from the registry. The defaults will be used only if a new register file is created.
        gain_p, gain_i, gain_d = self._node.registry.setdefault("thermostat.pid.gains", [0.12, 0.18, 0.01]).floats

        logging.info("Application started with PID gains: %.3f %.3f %.3f", gain_p, gain_i, gain_d)
        print("Running. Press Ctrl+C to stop.", file=sys.stderr)

        # This loop will exit automatically when the node is close()d. It is also possible to use receive() instead.
        async for m, _metadata in self._sub_t_pv:
            assert isinstance(m, uavcan.si.sample.temperature.Scalar_1_0)
            temperature_error = temperature_setpoint - m.kelvin
            voltage_output = temperature_error * gain_p  # Suppose this is a basic P-controller.
            await self._pub_v_cmd.publish(uavcan.si.unit.voltage.Scalar_1_0(voltage_output))

    def close(self) -> None:
        """
        This will close all the underlying resources down to the transport interface and all publishers/servers/etc.
        All pending tasks such as serve_in_background()/receive_in_background() will notice this and exit automatically.
        """
        self._node.close()


if __name__ == "__main__":
    app = DemoApp()
    logging.root.setLevel(logging.INFO)
    try:
        asyncio.get_event_loop().run_until_complete(app.run())
    except KeyboardInterrupt:
        pass
    finally:
        app.close()

If you just run the script as-is, you will notice that it fails with an error referring to some missing registers.

As explained in the comments (and — in great detail — in the UAVCAN Specification), registers are basically named values that keep various configuration parameters of the local UAVCAN node (application). Some of these parameters are used by the business logic of the application (e.g., PID gains); others are used by the UAVCAN stack (e.g., port-IDs, node-ID, transport configuration, logging, and so on). Registers of the latter category are all named with the same prefix uavcan., and their names and semantics are regulated by the Specification to ensure consistency across the ecosystem.

So the application fails with an error that says that it doesn’t know how to reach the UAVCAN network it is supposed to be part of because there are no registers to read that information from. We can resolve this by passing the correct register values via environment variables:

export UAVCAN__NODE__ID=42                           # Set the local node-ID 42 (anonymous by default)
export UAVCAN__UDP__IFACE=127.9.0.0                  # Use UAVCAN/UDP transport via 127.9.0.42 (sic!)
export UAVCAN__SUB__TEMPERATURE_SETPOINT__ID=2345    # Subject "temperature_setpoint"    on ID 2345
export UAVCAN__SUB__TEMPERATURE_MEASUREMENT__ID=2346 # Subject "temperature_measurement" on ID 2346
export UAVCAN__PUB__HEATER_VOLTAGE__ID=2347          # Subject "heater_voltage"          on ID 2347
export UAVCAN__SRV__LEAST_SQUARES__ID=123            # Service "least_squares"           on ID 123
export UAVCAN__DIAGNOSTIC__SEVERITY=2                # This is optional to enable logging via UAVCAN

python demo_app.py                                   # Run the application!

The snippet is valid for sh/bash/zsh; if you are using PowerShell on Windows, replace export with $env: and take values into double quotes. Further snippets will not include this remark.

An environment variable UAVCAN__SUB__TEMPERATURE_SETPOINT__ID sets register uavcan.sub.temperature_setpoint.id, and so on.

In PyUAVCAN, registers are normally stored in the register file, in our case it’s my_registers.db (the UAVCAN Specification does not regulate how the registers are to be stored, this is an implementation detail). Once you started the application with a specific configuration, it will store the values in the register file, so the next time you can run it without passing any environment variables at all.

The registers of any UAVCAN node are exposed to other network participants via the standard RPC-services defined in the standard DSDL namespace uavcan.register. This means that other nodes on the network can reconfigure our demo application via UAVCAN directly, without the need to resort to any secondary management interfaces. This is equally true for software nodes like our demo application and deeply embedded hardware nodes.

When you execute the commands above, you should see the script running. Leave it running and move on to the next section.

Tip

Just-in-time vs. ahead-of-time DSDL compilation

The script will transpile the required DSDL namespaces just-in-time at launch. While this approach works for some applications, those that are built for redistribution at large (e.g., via PyPI) may benefit from compiling DSDL ahead-of-time (at build time) and including the compilation outputs into the redistributable package. Ahead-of-time DSDL compilation can be trivially implemented in setup.py:

 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
#!/usr/bin/env python
# Distributed under CC0 1.0 Universal (CC0 1.0) Public Domain Dedication.
# type: ignore
"""
A simplified setup.py demo that shows how to distribute compiled DSDL definitions with Python packages.
"""

import setuptools
import logging
import distutils.command.build_py
from pathlib import Path

NAME = "demo_app"


# noinspection PyUnresolvedReferences
class BuildPy(distutils.command.build_py.build_py):
    def run(self):
        import pyuavcan

        pyuavcan.dsdl.compile_all(
            [
                "public_regulated_data_types/uavcan",  # All UAVCAN applications need the standard namespace, always.
                "custom_data_types/sirius_cyber_corp",
                # "public_regulated_data_types/reg",  # Many applications also need the non-standard regulated DSDL.
            ],
            output_directory=Path(self.build_lib, NAME, ".demo_dsdl_compiled"),  # Store in the build output archive.
        )
        super().run()


logging.basicConfig(level=logging.INFO, format="%(levelname)-3.3s %(name)s: %(message)s")

setuptools.setup(
    name=NAME,
    py_modules=["demo_app"],
    cmdclass={"build_py": BuildPy},
)

Poking the node using Yakut

The demo is running now so we can interact with it and see how it responds. We could write another script for that using PyUAVCAN, but in this section we will instead use Yakut — a simple CLI tool for diagnostics and management of UAVCAN networks. You will need to open a couple of new terminal sessions now.

If you don’t have Yakut installed on your system yet, install it now by following its documentation.

Yakut requires us to compile our DSDL namespaces beforehand using yakut compile:

yakut compile  custom_data_types/sirius_cyber_corp  public_regulated_data_types/uavcan

The outputs will be stored in the current working directory. If you decided to change the working directory or move the compilation outputs, make sure to export the YAKUT_PATH environment variable pointing to the correct location.

The commands shown later need to operate on the same network as the demo. Earlier we configured the demo to use UAVCAN/UDP via 127.9.0.42. So, for Yakut, we can export this configuration to let it run on the same network anonymously:

export UAVCAN__UDP__IFACE=127.9.0.0  # We don't export the node-ID, so it will remain anonymous.

To listen to the demo’s heartbeat and diagnostics, launch the following commands in new terminals and leave them running:

export UAVCAN__UDP__IFACE=127.9.0.0
yakut sub uavcan.node.Heartbeat.1.0     # You should see heartbeats being printed continuously.
export UAVCAN__UDP__IFACE=127.9.0.0
yakut sub uavcan.diagnostic.Record.1.1  # This one will not show anything yet -- read on.

Now let’s see how the simple thermostat node is operating. Launch another subscriber to see the published voltage command (it is not going to print anything yet):

export UAVCAN__UDP__IFACE=127.9.0.0
yakut sub -M 2347:uavcan.si.unit.voltage.Scalar.1.0     # Prints nothing.

And publish the setpoint along with measurement (process variable):

export UAVCAN__UDP__IFACE=127.9.0.0
export UAVCAN__NODE__ID=111         # We need a node-ID to publish messages
yakut pub --count 10 2345:uavcan.si.unit.temperature.Scalar.1.0   'kelvin: 250' \
                     2346:uavcan.si.sample.temperature.Scalar.1.0 'kelvin: 240'

You should see the voltage subscriber that we just started print something along these lines:

---
2347: {volt: 1.1999999284744263}

# And so on...

Okay, the thermostat is working. If you change the setpoint (via subject-ID 2345) or measurement (via subject-ID 2346), you will see the published command messages (subject-ID 2347) update accordingly.

One important feature of the register interface is that it allows one to monitor internal states of the application, which is critical for debugging. In some way it is similar to performance counters or tracing probes:

yakut call 42 uavcan.register.Access.1.0 'name: {name: thermostat.error}'

We will see the current value of the temperature error registered by the thermostat:

---
384:
  timestamp: {microsecond: 0}
  mutable: false
  persistent: false
  value:
    real32:
      value: [10.0]

Field mutable: false says that this register cannot be modified and persistent: false says that it is not committed to any persistent storage (like a register file). Together they mean that the value is computed at runtime dynamically.

We can use the very same interface to query or modify the configuration parameters. For example, we can change the PID gains of the thermostat:

yakut call 42 uavcan.register.Access.1.0 '{name: {name: thermostat.pid.gains}, value: {integer8: {value: [2, 0, 0]}}}'

Which results in:

---
384:
  timestamp: {microsecond: 0}
  mutable: true
  persistent: true
  value:
    real64:
      value: [2.0, 0.0, 0.0]

An attentive reader would notice that the assigned value was of type integer8, whereas the result is real64. This is because the register server does implicit type conversion to the type specified by the application. The UAVCAN Specification does not require this behavior, though, so some simpler nodes (embedded systems in particular) may just reject mis-typed requests.

If you restart the application now, you will see it use the updated PID gains.

Now let’s try the linear regression service:

yakut call 42 123:sirius_cyber_corp.PerformLinearLeastSquaresFit.1.0 'points: [{x: 10, y: 3}, {x: 20, y: 4}]'

The response should look like:

---
123:
  slope: 0.1
  y_intercept: 2.0

And the diagnostic subscriber we started in the beginning (type uavcan.diagnostic.Record) should print a message.

Second node

To make this tutorial more hands-on, we are going to add another node and make it interoperate with the first one. As the first node implements a basic thermostat, the second one simulates the plant whose temperature is controlled by the thermostat. Put the following into plant.py in the same directory:

 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
#!/usr/bin/env python3
# Distributed under CC0 1.0 Universal (CC0 1.0) Public Domain Dedication.
"""
This application simulates the plant controlled by the thermostat node: it takes a voltage command,
runs a crude thermodynamics simulation, and publishes the temperature (i.e., one subscription, one publication).
"""

import time
import asyncio
import uavcan.si.unit.voltage
import uavcan.si.sample.temperature
import uavcan.time
import pyuavcan
from pyuavcan.application.heartbeat_publisher import Health
from pyuavcan.application import make_node, NodeInfo, register


UPDATE_PERIOD = 0.5

heater_voltage = 0.0
saturation = False


async def handle_command(msg: uavcan.si.unit.voltage.Scalar_1_0, _metadata: pyuavcan.transport.TransferFrom) -> None:
    global heater_voltage, saturation
    if msg.volt < 0.0:
        heater_voltage = 0.0
        saturation = True
    elif msg.volt > 50.0:
        heater_voltage = 50.0
        saturation = True
    else:
        heater_voltage = msg.volt
        saturation = False


async def main() -> None:
    with make_node(NodeInfo(name="org.uavcan.pyuavcan.demo.plant"), "plant.db") as node:
        # Expose internal states for diagnostics.
        node.registry["status.saturation"] = lambda: saturation  # The register type will be deduced as "bit[1]".

        # Initialize values from the registry. The temperature is in kelvin because in UAVCAN everything follows SI.
        # Here, we specify the type explicitly as "real32[1]". If we pass a native float, it would be "real64[1]".
        temp_environment = float(node.registry.setdefault("model.environment.temperature", register.Real32([292.15])))
        temp_plant = temp_environment

        # Set up the ports.
        pub_meas = node.make_publisher(uavcan.si.sample.temperature.Scalar_1_0, "temperature")
        pub_meas.priority = pyuavcan.transport.Priority.HIGH
        sub_volt = node.make_subscriber(uavcan.si.unit.voltage.Scalar_1_0, "voltage")
        sub_volt.receive_in_background(handle_command)

        # Run the main loop forever.
        next_update_at = node.loop.time()
        while True:
            # Publish new measurement and update node health.
            await pub_meas.publish(
                uavcan.si.sample.temperature.Scalar_1_0(
                    timestamp=uavcan.time.SynchronizedTimestamp_1_0(microsecond=int(time.time() * 1e6)),
                    kelvin=temp_plant,
                )
            )
            node.heartbeat_publisher.health = Health.ADVISORY if saturation else Health.NOMINAL

            # Sleep until the next iteration.
            next_update_at += UPDATE_PERIOD
            await asyncio.sleep(next_update_at - node.loop.time())

            # Update the simulation.
            temp_plant += heater_voltage * 0.1 * UPDATE_PERIOD  # Energy input from the heater.
            temp_plant -= (temp_plant - temp_environment) * 0.05 * UPDATE_PERIOD  # Dissipation.


if __name__ == "__main__":
    try:
        asyncio.get_event_loop().run_until_complete(main())
    except KeyboardInterrupt:
        pass

You may launch it if you want, but you will notice that tinkering with registers by way of manual configuration gets old fast. The next section introduces a better way.

Orchestration

Attention

Yakut Orchestrator is in the alpha stage. Breaking changes may be introduced between minor versions until Yakut v1.0 is released. Freeze the minor version number to avoid unexpected changes.

Yakut Orchestrator does not support Windows at the moment.

Manual management of environment variables and node processes may work in simple setups, but it doesn’t really scale. Practical cyber-physical systems require a better way of managing UAVCAN networks that may simultaneously include software nodes executed on the local or remote computers along with specialized bare-metal nodes running on dedicated hardware.

One solution to this is Yakut Orchestrator — an interpreter of a simple YAML-based domain-specific language that allows one to define process groups and conveniently manage them as a single entity. The language comes with a user-friendly syntax for managing UAVCAN registers. Those familiar with ROS may find it somewhat similar to roslaunch.

The following orchestration file (orc-file) launch.orc.yaml does this:

  • Compiles two DSDL namespaces: the standard uavcan and the custom sirius_cyber_corp. If they are already compiled, this step is skipped.

  • When compilation is done, the two applications are launched.

  • Aside from the applications, a couple of diagnostic processes are started as well. A setpoint publisher will command the thermostat to drive the plant to the specified temperature.

The orchestrator runs everything concurrently, but join statements are used to enforce sequential execution as needed. The first process to fail (that is, exit with a non-zero code) will bring down the entire composition. Predicate scripts ?= are allowed to fail though — this is used to implement conditional execution.

The syntax allows the developer to define regular environment variables along with register names. The latter are translated into environment variables when starting a process.

 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
#!/usr/bin/env -S yakut --verbose orchestrate
# Read the docs about the orc-file syntax: yakut orchestrate --help

# Shared environment variables for all nodes/processes (can be overridden or selectively removed in local scopes).
YAKUT_COMPILE_OUTPUT: .yakut_compiled
YAKUT_PATH: .yakut_compiled
# Here we use Yakut for compiling DSDL. Normally one should use Nunavut though: https://github.com/UAVCAN/nunavut
PYTHONPATH: .yakut_compiled

# Shared registers for all nodes/processes (can be overridden or selectively removed in local scopes).
# See the docs for pyuavcan.application.make_node() to see which registers can be used here.
uavcan:
  # Use UAVCAN/UDP:
  udp.iface: 127.9.0.0
  # If you have Ncat or some other TCP broker, you can use UAVCAN/serial tunneled over TCP (in a heterogeneous
  # redundant configuration with UDP or standalone). Ncat launch example: ncat --broker --listen --source-port 50905
  serial.iface: "" # socket://127.0.0.1:50905
  # It is recommended to explicitly assign unused transports to ensure that previously stored transport
  # configurations are not accidentally reused:
  can.iface: ""
  # Configure diagnostic publishing, too:
  diagnostic:
    severity: 2
    timestamp: true

# Keys with "=" define imperatives rather than registers or environment variables.
$=:
- ?=: '[ ! -d $YAKUT_COMPILE_OUTPUT ]'  # If the output directory does not exist, run the Yakut DSDL compiler.
  $=:                                   # All script statements run concurrently.
  - echo "Compiling DSDL, this may take a while"
  - yakut compile custom_data_types/sirius_cyber_corp public_regulated_data_types/uavcan

- # An empty statement is a join statement -- wait for the previously launched processes to exit before continuing.

- $=:
  # Wait a bit to let the diagnostic subscribers get ready (they are launched below).
  - sleep 1
  - # Remember, everything runs concurrently by default, but this join statement waits for the sleep to exit.

  # Launch the demo app that implements the thermostat.
  - $=: python demo_app.py
    uavcan:
      node.id: 42
      sub.temperature_setpoint.id:    2345
      sub.temperature_measurement.id: 2346
      pub.heater_voltage.id:          2347
      srv.least_squares.id:           0xFFFF    # We don't need this service. Disable by setting an invalid port-ID.
    thermostat:
      pid.gains: [0.1, 0, 0]

  # Launch the controlled plant simulator.
  - $=: python plant.py
    uavcan:
      node.id: 43
      sub.voltage.id:     2347
      pub.temperature.id: 2346
    model.environment.temperature: 300.0    # In UAVCAN everything follows SI, so this temperature is in kelvin.

  # Publish the setpoint a few times to show how the thermostat drives the plant to the correct temperature.
  # You can publish a different setpoint by running this command in a separate terminal to see how the system responds:
  #   $ yakut -i "UDP('127.9.0.0', 100)" pub 2345:uavcan.si.unit.temperature.Scalar.1.0 "kelvin: 200"
  - $=: |
      yakut pub 2345:uavcan.si.unit.temperature.Scalar.1.0 "kelvin: 450.0" -N3
    uavcan.node.id: 100

# Launch diagnostic subscribers to print messages in the terminal that runs the orchestrator.
- yakut subscribe uavcan.diagnostic.Record.1.1
- yakut --format=json subscribe --no-metadata 2346:uavcan.si.sample.temperature.Scalar.1.0

# Exit automatically if STOP_AFTER is defined (frankly, this is just a testing aid, feel free to ignore).
- ?=: test -n "$STOP_AFTER"
  $=: sleep $STOP_AFTER && exit 111

Terminate the first node before continuing since it is now managed by the orchestration script we just wrote. Ensure that the node script files are named demo_app.py and plant.py, otherwise the orchestrator won’t find them.

The orc-file can be executed as yakut orc launch.orc.yaml, or simply ./launch.orc.yaml (use --verbose to see which environment variables are passed to each launched process). Having started it, you should see roughly the following output appear in the terminal, indicating that the thermostat is driving the plant towards the setpoint:

---
8184:
  _metadata_:
    timestamp: {system: 1614489567.052270, monotonic: 4864.397568}
    priority: optional
    transfer_id: 0
    source_node_id: 42
  timestamp: {microsecond: 1614489567047461}
  severity: {value: 2}
  text: 'root: Application started with PID gains: 0.100 0.000 0.000'

{"2346":{"timestamp":{"microsecond":1614489568025004},"kelvin":300.0}}
{"2346":{"timestamp":{"microsecond":1614489568524508},"kelvin":300.7312622070312}}
{"2346":{"timestamp":{"microsecond":1614489569024634},"kelvin":301.4406433105469}}
{"2346":{"timestamp":{"microsecond":1614489569526189},"kelvin":302.1288757324219}}

# And so on. Notice how the temperature is rising slowly towards the setpoint at 450 K!

As an exercise, consider this:

  • Run the same composition over CAN by changing the transport configuration registers at the top of the orc-file. The full set of transport-related registers is documented at pyuavcan.application.make_transport().

  • Implement saturation management by publishing the saturation flag over a dedicated subject and subscribing to it from the thermostat node.

  • Use Wireshark (capture filter expression: (udp or igmp) and src net 127.9.0.0/16) or candump (like candump -decaxta any) to inspect the network exchange.