• Specification
    • 1. Introduction
    • 2. Basic concepts
    • 3. Data structure description language
    • 4. CAN bus transport layer
    • 5. Application level conventions
    • 6. Application level functions
    • 7. List of standard data types
    • 8. Hardware design recommendations
  • Implementations
    • Libuavcan
      • Platforms
      • Tutorials
        • 1. Library build configuration
        • 2. Node initialization and startup
        • 3. Publishers and subscribers
        • 4. Services
        • 5. Timers
        • 6. Time synchronization
        • 7. Remote node reconfiguration
        • 8. Custom data types
        • 9. Node discovery
        • 10. Dynamic node ID allocation
        • 11. Firmware update
        • 12. Multithreading
        • 13. CAN acceptance filters
      • FAQ
    • Pyuavcan
      • Examples
        • Automated ESC enumeration
        • ESC throttle control
      • Tutorials
        • 1. Setup
        • 2. Basic usage
        • 3. Advanced usage
        • 4. Parsing DSDL definitions
    • Libcanard
    • Uavcan.rs
  • GUI Tool
    • Overview
    • Examples
    • User guide
  • Examples
    • Simple sensor node
  • Forum
Implementations /  Libuavcan /  Tutorials /  2. Node initialization and startup

Node initialization and startup

In this tutorial we’ll create a simple node that doesn’t do anything useful yet.

Abstract

In order to add UAVCAN functionality into an application, we’ll have to create a node object of class uavcan::Node, which is the cornerstone of the library’s API. The class requires access to the CAN driver and the system clock, which are platform-specific components, therefore they are isolated from the library through the following interfaces:

  • uavcan::ICanDriver
  • uavcan::ICanIface
  • uavcan::ISystemClock

Classes that implement above interfaces are provided by libuavcan platform drivers. Applications that are using libuavcan can be easily ported between platforms by means of swapping the implementations of these interfaces.

Memory management

Libuavcan does not use heap.

Dynamic memory

Dynamic memory allocations are managed by constant-time determenistic fragmentation-free block memory allocator. The size of the memory pool that is dedicated to block allocation should be defined compile-time through a template argument of the node class uavcan::Node. If the template argument is not provided, the node will expect the application to provide a reference to a custom allocator to the constructor (custom allocators are explained below).

The library uses dynamic memory for the following tasks:

  • Allocation of temporary buffers for reception of multi-frame transfers;
  • Keeping receiver states (refer to the transport layer specification for more info);
  • Keeping transfer ID map (refer to the transport layer specification for more info);
  • Prioritized TX queue;
  • Some high-level logic.

Typically, the size of the memory pool will be between 4 KB (for a simple node) and 512 KB (for a very complex node). The minimum safe size of the memory pool can be evaluated as a double of the sum of the following values:

  • For every incoming data type, multiply its maximum serialized length to the number of nodes that may publish it and add up the results.
  • Sum the maximum serialized length of all outgoing data types and multiply to the number of CAN interfaces available to the node plus one.

It is recommended to round the result up to 64-byte boundary.

Memory pool sizing example

Consider the following example:

Property Value
Number of CAN interfaces 2
Number of publishers of the data type A 3
Maximum serialized length of the data type A 100 bytes
Number of publishers of the data type B 32
Maximum serialized length of the data type B 24 bytes
Maximum serialized length of the data type X 256 bytes
Maximum serialized length of the data type Z 10 bytes

A node that is interested in receiving data types A and B, and in publishing data types X and Y, will require at least the following amount of memory for the memory pool:

2 * ((3 * 100 + 32 * 24) + (2 + 1) * (256 + 10)) = 3732 bytes
Round up to 64: 3776 bytes.
Memory gauge

The library allows to query current memory use as well as peak (worst case) memory use with the following methods of the class PoolAllocator<>:

  • uint16_t getNumUsedBlocks() const - returns the number of blocks that are currently in use.
  • uint16_t getNumFreeBlocks() const - returns the number of blocks that are currently free.
  • uint16_t getPeakNumUsedBlocks() const - returns the peak number of blocks allocated, i.e. worst case pool usage.

The methods above can be accessed as follows:

std::cout << node.getAllocator().getNumUsedBlocks()     << std::endl;
std::cout << node.getAllocator().getNumFreeBlocks()     << std::endl;
std::cout << node.getAllocator().getPeakNumUsedBlocks() << std::endl;

The example above assumes that the node object is named node.

Custom allocators

The node classes can accept a custom allocator provided by the application instead of using a default one. In order to use a custom allocator, omit the template argument to the node class, and provide a reference to uavcan::IPoolAllocator to the node class constructor.

The library implements an alternative allocator that uses heap memory instead of a statically allocated pool. It can be found under uavcan/helpers/heap_based_pool_allocator.hpp. Please read the class documentation for more info.

The tutorial dedicated to multithreading also covers the topic of custom allocators.

Stack allocation

Deserialized message and service objects are allocated on the stack. Therefore, the size of the stack available to the thread must account for the largest used message or service object. This also implies that any reference to a message or service object passed to the application via a callback will be invalidated once the callback returns control back to the library.

Typically, minimum safe size of the stack would be about 1.5 KB.

Threading

From the standpoint of threading, the following configurations are available:

  • Single-threaded - the library runs entirely in a single thread.
  • Multi-threaded - the library runs in two threads:
    • Primary thread, which is suitable for hard real time, low-latency communications;
    • Secondary threads, which are suitable for blocking, I/O-intensive, or CPU-intensive tasks, but not for real-time tasks.

Single-threaded configuration

In a single-threaded configuration, the library’s thread should either always block inside Node<>::spin(), or invoke Node<>::spin() or Node<>::spinOnce() periodically.

Blocking inside spin()

This is the most typical use-case:

for (;;)
{
    const int error = node.spin(uavcan::MonotonicDuration::fromMSec(100));
    if (error < 0)
    {
        std::cerr << "Transient error: " << error << std::endl; // Handle the transient error...
    }
}

Some background processing can be performed between the calls to spin():

for (;;)
{
    const int error = node.spin(uavcan::MonotonicDuration::fromMSec(100));
    if (error < 0)
    {
        std::cerr << "Transient error: " << error << std::endl; // Handle the transient error...
    }

    performBackgroundProcessing();  // Will be invoked between spin() calls, at 10 Hz in this example
}

In the latter example, the function performBackgroundProcessing() will be invoked at 10 Hz between calls to Node<>::spin(). The same effect can be achieved with libuavcan’s timer objects, which will be covered in the following tutorials.

Blocking outside of spin()

This is a more involved use case. This approach can be useful if the application needs to poll various I/O operations in the same thread with libuavcan.

In this case, the application will have to obtain the file descriptor from the UAVCAN’s CAN driver object, and add it to the set of file descriptors it is polling on. Whenever the CAN driver’s file descriptor reports an event, the application will call either Node<>::spin() or Node<>::spinOnce(). Also, the spin method must be invoked periodically; the recommended maximum period is 10 milliseconds.

The difference between Node<>::spin() and Node<>::spinOnce() is as follows:

  • spin() - blocks until the timeout has expired, then returns, even if some of the CAN frames or timer events are still pending processing.
  • spinOnce() - instead of blocking, it returns immediately once all available CAN frames and timer events are processed.

Multi-threaded configuration

This configuration is covered later in a dedicated tutorial. In short, it splits the node into multiple node objects, where each node object is being maintained in a separate thread. The same concepts concerning the spin methods apply as for the single-threaded configuration (see above).

Typically, the separated node objects communicate with each other by means of a virtual CAN driver interface.

The code

Put the following code into node.cpp:

#include <iostream>
#include <cstdlib>
#include <unistd.h>
#include <uavcan/uavcan.hpp>

/**
 * These functions are platform dependent, so they are not included in this example.
 * Refer to the relevant platform documentation to learn how to implement them.
 */
extern uavcan::ICanDriver& getCanDriver();
extern uavcan::ISystemClock& getSystemClock();

/**
 * Memory pool size largely depends on the number of CAN ifaces and on application's logic.
 * Please read the documentation for the class uavcan::Node to learn more.
 */
constexpr unsigned NodeMemoryPoolSize = 16384;

typedef uavcan::Node<NodeMemoryPoolSize> Node;

/**
 * Node object will be constructed at the time of the first access.
 * Note that most library objects are noncopyable (e.g. publishers, subscribers, servers, callers, timers, ...).
 * Attempt to copy a noncopyable object causes compilation failure.
 */
static Node& getNode()
{
    static Node node(getCanDriver(), getSystemClock());
    return node;
}

int main(int argc, const char** argv)
{
    if (argc < 2)
    {
        std::cerr << "Usage: " << argv[0] << " <node-id>" << std::endl;
        return 1;
    }

    const int self_node_id = std::stoi(argv[1]);

    /*
     * Node initialization.
     * Node ID and name are required; otherwise, the node will refuse to start.
     * Version info is optional.
     */
    auto& node = getNode();

    node.setNodeID(self_node_id);

    node.setName("org.uavcan.tutorial.init");

    uavcan::protocol::SoftwareVersion sw_version;  // Standard type uavcan.protocol.SoftwareVersion
    sw_version.major = 1;
    node.setSoftwareVersion(sw_version);

    uavcan::protocol::HardwareVersion hw_version;  // Standard type uavcan.protocol.HardwareVersion
    hw_version.major = 1;
    node.setHardwareVersion(hw_version);

    /*
     * Start the node.
     * All returnable error codes are listed in the header file uavcan/error.hpp.
     */
    const int node_start_res = node.start();
    if (node_start_res < 0)
    {
        throw std::runtime_error("Failed to start the node; error: " + std::to_string(node_start_res));
    }

    /*
     * Informing other nodes that we're ready to work.
     * Default mode is INITIALIZING.
     */
    node.setModeOperational();

    /*
     * Some logging.
     * Log formatting is not available in C++03 mode.
     */
    node.getLogger().setLevel(uavcan::protocol::debug::LogLevel::DEBUG);
    node.logInfo("main", "Hello world! My Node ID: %*",
                 static_cast<int>(node.getNodeID().get()));

    std::cout << "Hello world!" << std::endl;

    /*
     * Node loop.
     * The thread should not block outside Node::spin().
     */
    while (true)
    {
        /*
         * If there's nothing to do, the thread blocks inside the driver's
         * method select() until the timeout expires or an error occurs (e.g. driver failure).
         * All error codes are listed in the header uavcan/error.hpp.
         */
        const int res = node.spin(uavcan::MonotonicDuration::fromMSec(1000));
        if (res < 0)
        {
            std::cerr << "Transient failure: " << res << std::endl;
        }

        /*
         * Random status transitions.
         * In real applications, the status code shall reflect node's health.
         */
        const float random = std::rand() / float(RAND_MAX);
        if (random < 0.7)
        {
            node.setHealthOk();
        }
        else if (random < 0.9)
        {
            node.setHealthWarning();
        }
        else
        {
            node.setHealthError();
        }
    }
}

Running on Linux

We need to implement the platform-specific functions declared in the beginning of the example code above, write a build script, and then build the application. For the sake of simplicity, it is assumed that there’s a single CAN interface named vcan0.

Libuavcan must be installed on the system in order for the build to succeed. Also take a look at the CLI tools that come with the libuavcan Linux platform driver - they will be helpful when learning from the tutorials.

Implementing the platform-specific functions

Put the following code into platform_linux.cpp:

#include <uavcan_linux/uavcan_linux.hpp>

uavcan::ISystemClock& getSystemClock()
{
    static uavcan_linux::SystemClock clock;
    return clock;
}

uavcan::ICanDriver& getCanDriver()
{
    static uavcan_linux::SocketCanDriver driver(dynamic_cast<const uavcan_linux::SystemClock&>(getSystemClock()));
    if (driver.getNumIfaces() == 0)     // Will be executed once
    {
        if (driver.addIface("vcan0") < 0)
        {
            throw std::runtime_error("Failed to add iface");
        }
    }
    return driver;
}

Writing the build script

We’re going to use CMake, but other build systems will work just as well. Put the following code into CMakeLists.txt:

cmake_minimum_required(VERSION 2.8)

project(tutorial_project)

find_library(UAVCAN_LIB uavcan REQUIRED)

set(CMAKE_CXX_FLAGS "-Wall -Wextra -pedantic -std=c++11")

add_executable(node node.cpp platform_linux.cpp)
target_link_libraries(node ${UAVCAN_LIB} rt)

Building

The building is quite standard for CMake:

mkdir build
cd build
cmake ..
make -j4

When these steps are executed, the application can be launched.

Using virtual CAN interface

It is convenient to test CAN applications against virtual CAN interfaces. In order to add a virtual CAN interface, execute the following:

IFACE="vcan0"

modprobe can
modprobe can_raw
modprobe can_bcm
modprobe vcan

ip link add dev $IFACE type vcan
ip link set up $IFACE

ifconfig $IFACE up

Libuavcan also includes utility uavcan_add_vcan that automates the procedure. For example:

uavcan_add_vcan vcan0

Execute uavcan_add_vcan --help to get usage info.

Using SLCAN (tunneling CAN over serial port)

Libuavcan includes an utility named uavcan_add_slcan that allows to easily configure an SLCAN interface. For example:

uavcan_add_slcan /dev/ttyACM0

Execute uavcan_add_slcan --help to get full usage info.

Note that SLCAN support requires that the package can-utils is installed on the system. On a Debian/Ubuntu-based system the package can be installed from APT: apt-get install can-utils. If this package is not available for your Linux distribution, you can build it from sources.

In certain cases SLCAN adapters may be losing TX frames due to insufficient capacity of the interface’s TX queue. This can be easily solved by means of providing larger TX queue for the interface:

ifconfig slcan0 txqueuelen 100     # Where 'slcan0' is the interface and '100' is queue depth

Using candump

candump is a tool from the package can-utils that can be used to monitor CAN bus traffic.

candump -caeta vcan0

You can always combine it with grep and other standard tools for advanced data processing, for example:

# Ignore status messages of node 121:
candump -caetz slcan0 | grep -v '\S\S015579'
# Print only messages from node 10 except its status messages:
candump -caetz slcan0 | grep '\S\S\S\S\S\S0A' | grep -v '\S\S01550A'
# Dump exchange to a file for later analysis:
candump -caetz slcan0 > can_`date -Iseconds`.dump

Learn how to grep from the grep manual.

Running on STM32

The platform-specific functions can be implemented as follows:

#include <uavcan_stm32/uavcan_stm32.hpp>

static constexpr int RxQueueSize = 64;
static constexpr std::uint32_t BitRate = 1000000;

uavcan::ISystemClock& getSystemClock()
{
    return uavcan_stm32::SystemClock::instance();
}

uavcan::ICanDriver& getCanDriver()
{
    static uavcan_stm32::CanInitHelper<RxQueueSize> can;
    static bool initialized = false;
    if (!initialized)
    {
        initialized = true;
        int res = can.init(BitRate);
        if (res < 0)
        {
            // Handle the error
        }
    }
    return can.driver;
}

For the rest, please refer to the STM32 test application provided in the repository.

Running on LPC11C24

The platform-specific functions can be implemented as follows:

#include <uavcan_lpc11c24/uavcan_lpc11c24.hpp>

static constexpr std::uint32_t BitRate = 1000000;

uavcan::ISystemClock& getSystemClock()
{
    return uavcan_lpc11c24::SystemClock::instance();
}

uavcan::ICanDriver& getCanDriver()
{
    static bool initialized = false;
    if (!initialized)
    {
        initialized = true;
        int res = uavcan_lpc11c24::CanDriver::instance().init(BitRate);
        if (res < 0)
        {
            // Handle the error
        }
    }
    return uavcan_lpc11c24::CanDriver::instance();
}

For the rest, please refer to the LPC11C24 test application provided in the repository.

Obsolete

This website is dedicated to the experimental version of the protocol known as UAVCAN v0 that is now obsolete. To learn more about the stable release UAVCAN v1.0, please visit the main website.

Libuavcan

  • Platforms
  • Tutorials
    • 1. Library build configuration
    • 2. Node initialization and startup
    • 3. Publishers and subscribers
    • 4. Services
    • 5. Timers
    • 6. Time synchronization
    • 7. Remote node reconfiguration
    • 8. Custom data types
    • 9. Node discovery
    • 10. Dynamic node ID allocation
    • 11. Firmware update
    • 12. Multithreading
    • 13. CAN acceptance filters
  • FAQ

License

This work is licensed under a Creative Commons Attribution 4.0 International License.
  • Discussion forum
  • GitHub organization
  • Report a problem with this website

Generated Thu, 17 Feb 2022 16:27:38 +0000 © UAVCAN development team