NUClear

Introduction to NUClear and how it is used in the NUbots codebase.
Ysobel Sims GitHub avatarCameron Murtagh GitHub avatar
Updated 1 Oct 2023

NUClear is the software framework used in the main NUbots codebase. It is a message passing system designed to be modular and fast.

This page is intended to be a practical summary of the official NUClear documentation, which contains a detailed description of NUClear. The NUClear Roles repository contains a detailed description of the NUClear roles system, much of which the roles section in this page is based off.

Components

PowerPlant

A collection of Reactors around the PowerPlant in the center. Double ended arrows point to and from the PowerPlant to each Reactor.
PowerPlant with Reactors. Image: https://nuclear.readthedocs.io/en/latest/components.html

The PowerPlant is the central message system through which reactors communicate. It takes ownership of any data emitted by reactors into the system and executes the required reactions. NUClear is multi-threaded. The PowerPlant handles all threading logic.

Reactors

A reactor can be thought of as a module. All modules in the NUClear system are an extension of NUClear::Reactor. Reactors define reactions and the conditions under which they will process. They may also emit data to the PowerPlant.

Reactions and Tasks

Reactions run tasks when the required data is available and/or when certain conditions are true. A task is the current execution of a defined reaction within the system. These functions are bound by NUClear as callbacks, and it is the execution of these callbacks which will assign tasks to a thread.

Reactions are created by subscribing to the PowerPlant through DSL On Statements.

NUClear DSL

On Statements

Reactors make subscriptions to the PowerPlant using on statements, which define the conditions for reactions to run.

An on statement has the following form

on<...>(...).then(...);

This can be split into three parts. The first is the on<...> which is the DSL request. The (...) contains any runtime arguments. .then(...); is the callback, which is what will be executed when the reaction is triggered.

DSL Request

The DSL request is "fused" together by combining any number of DSL words. The combination of these words will define the kind of reaction which is being requested. For example, Trigger will define a reaction that should occur when a required data type is emitted, while Every will define periodic reactions.

For reactions to occur, at least one Binding DSL word should be present in the DSL Request. The binding DSL words are: Trigger, With, Every, Always, Startup, Shutdown, TCP, UDP, and Network.

DSL WordDescription
TriggerIs used to request data dependent reactions. on<Trigger<T>>() will execute the task whenever T is emitted into the system. Read only access to T is given via a callback. on<Trigger<T1, T2, ... >>() requires multiple types and will only trigger when all the trigger types have been emitted at least once since the last occurrence of the event.
WithIs used to define any extra data which should be provided to a subscribing reaction. This should be fused with at least one other DSL word as the use of this word alone will not trigger a reaction within the system. on<Trigger<T1>, With<T2>>() will trigger when T1 is emitted into the system. It will give read-only access of T1 and T2 to the callback. If T2 is not present when T1 is emitted to the system, the reaction will not run.
LastInstructs the PowerPlant to store the last nn messages received (of the associated type) to the cache and provide read-only access to the subscribing reaction. on<Last<n, Trigger<T, ...>>>() will store the next nn messages of each of the Trigger types in a list with the oldest message first. After nn messages are stored, the trigger of a new reaction will cause the oldest message to be dropped and the newest copy appended to the list.
OptionalIs used to signify any optional properties in the DSL request. on<Trigger<T1>, Optional<With<T2>>>() will run when T1 is emitted into the system. If T2 is available, then the reaction will be given read-only access to the most recent emission of T2. If it is not available, it will give the callback a nullptr.
SingleIs used to specify that only one instance of the associated reaction can execute at any given point during runtime. on<Trigger<T, ...>, Single>() will only allow one task for this reaction to be executed or in the queue at any given time. This should be fused with another DSL word, such as Trigger in the example. This word is equivalent to Buffer<1>.
BufferIs used to specify that up to nn instances of the associated reaction can execute during runtime. on<Trigger<T, ...>, Buffer<n>>>() will create and schedule a new task if there are less than nn existing tasks for this reaction. This should be fused with another DSL word, such as Trigger in the example. Buffer<1> is equivalent to Single.
PriorityAssigns a priority to any tasks created to determine scheduling order in the PowerPlant. on<Trigger<T, ...>, Priority::HIGH>() will schedule the task with HIGH priority when the reaction is triggered. Available priority settings are REALTIME, HIGH, NORMAL, LOW, and IDLE. This should be fused with another DSL word, such as Trigger in the example.
SyncSets the synchronisation for a group of tasks. on<Trigger<T, ...>, Sync<Group>>() will allow only one task from Group to execute at any given time. Tasks will be queued if there is already a task from this Group running. This word helps prevent race conditions. This should be fused with another DSL word, such as Trigger in the example.
EveryUsed to request periodic reactions in the system. on<Every<2, std::chrono::seconds>() will create a task every two seconds. on<Every<2, Per<std::chrono::seconds>>() will create a task two times per second.
AlwaysUsed to request continuous reactions in the system. on<Always> will ensure a single instance of the associated reaction is running at all times. Always runs in its own thread rather than using the thread pool.
StartupUsed to specify reactions which should occur at startup. on<Startup>() will create a task after all reactors have been installed into the PowerPlant but before the system starts the main execution phase.
ShutdownUsed to specify any reactions/tasks which should occur during shutdown. on<Shutdown>() will create a task after the shutdown command has been emitted and all existing tasks have completed.
IOUsed to trigger reactions based on standard I/O operations using file descriptors. on<IO>(pipe/stream/comms, io_status) will create a task when the communication line matches the given status. For example, on<IO>(my_file_descriptor, IO::READ) will create the task when the given file descriptor has data available to read.
NetworkNUClear provides a networking protocol to send messages to other devices on the network. on<Network<T>>() will create a task when T is emitted using the emission type Scope::NETWORK.
ConfigurationUsed to set configuration values. File name is a runtime argument. Is of the form on<Configuration>("Config.yaml").then(...). The runtime argument can also be a folder to enable monitoring for all changes in that folder.

More information on DSL words for on statements can be found in the NUClear documentation.

Runtime arguments

Some DSL words will provide the ability to make changes to the system during runtime. This means that NUClear avoids the need for a system restart should a configuration, port number, or file need to be changed while the system is running.

The DSL words that take runtime arguments are: IO, TCP, UDP and Configuration.

Callback

The callback which will execute when the reaction is triggered during runtime can be defined using a C++ lambda function. These are of the form

[this](args...){
statements...
}

The args will generally be based off the conditions for the reaction, such as access to data. For example:

on<Trigger<dataType>>().then([this](const dataType& value) {
// Do things
});

Capturing the this pointer will allow your reaction to access other members of your Reactor (e.g. configuration data).

Emit Statements

Emit statements are used by Reactors wanting to emit data to the PowerPlant. When using NUClear, data will most likely be emitted during a reaction. However, where necessary, emissions can also occur during reactor construction, or in some cases from within the PowerPlant itself.

Any data emitted to the PowerPlant will be sent with a unique pointer. The PowerPlant will take ownership of this pointer and run any necessary callbacks to trigger reactions.

Data can be emitted under varying scopes. These can be local or network emissions. More information can be found on emit statements in the NUClear documentation.

Local Emissions

Local emissions send data to the local instance of the NUClear PowerPlant. Essentially this is the current running process. There are a number of scopes under which these emissions can take place. The syntax for these emissions are emit<Scope::SCOPE>(data, args...);, where SCOPE is replaced with a scope as defined below.

ScopeDescription
LOCALWhen emitting data under this scope, tasks are distributed via the thread pool for execution. This is the default behaviour when emitting.
DIRECTWhen emitting data under this scope, the tasks created as a result of this emission will bypass the threadpool, and be executed immediately.
INITIALISEThis scope emits data as the system starts up.
DELAYThis will emit data, after the provided delay. The syntax includes a delay time emit<Scope::DELAY>(data, delay(ticks));.

Network Emitting

Network emissions can be used to send data through the network on which the current system is running.

ScopeDescription
UDPEmits data as a UDP packet over the network. Is of the form emit<Scope::UDP>(data, to_addr, to_port);.
NETWORKEmits data over the network to other NUClear environments. Is of the form emit<Scope::NETWORK>(data, target, reliable);. The reliable flag, if true, will cause NUClear to continue sending the data until it receives an ACKnowledgement from the target.

Managing Reactions

During system runtime, executing reactions can be managed via their associated reaction handles. A reaction handle is provided for binding on statements. Once an on statement has been bound, the reaction handle will be enabled. If necessary, reactions can toggle between enabled and disabled during runtime.

HandleDescription
disable()Disables the reaction. Tasks will not be created if triggered.
enable()Enables the reaction so that associated tasks will be scheduled and queued when the reaction is triggered.
enable(bool set)Sets the run status of the reaction handle. true will enable the reaction and false will disable it.
enabled()Determines the current status of the reaction. Returns true if the reaction is enabled, and false otherwise.
unbind()Removes a reaction request from the runtime environment. This action is not reversible, once a reaction has been unbound, it is no longer available for further use during that runtime.

NUClear Roles

The NUClear Roles system is a build and messaging system for the NUClear framework. It uses CMake and Python to manage the construction of various executables made up of a selection of modules. These executables are called roles.

CMake is used as the main system for generating the libraries and executables that are used for the final binary. Note that it utilises globbing to find the sources that are used for modules. If you add or remove a file, you must rerun CMake to locate the new files.

Directories

There are six main directories in the NUClear Roles system and can be seen in the main NUbots codebase.

DirectoryDescription
modulecontains the NUClear reactors. Is broken into the various subsystems. These are behaviour, extension, input, localisation, motion, output, platform, support, tools and vision.
messagecontains the message types for the system. The message folder is located in the shared directory. This is broken into the various subsystems much like the module directory.
extensioncontains any NUClear DSL extensions, such as Configuration. This is located in the shared directory.
utilitycontains utility code that is shared amongst NUClear Reactors, such as Kinematics and Mathematics utilities. This is located in the shared directory.
rolescontains all the NUClear role files.
toolscontains any command line extensions for the b script, such as build and configure.

Roles

Roles are executables containing a specified list of modules. They are called <executablename>.role, where <executablename> is the name of the final binary that will be created.

The name of each module is described as a fully qualified C++ class without the initial module namespace. These modules will then be installed in order when the executable is run. This is important to note as it means modules that have dependencies on other modules may want to be lower in the list. For example installing log handler modules should happen before installing other modules so their output can be seen. It will use this name to locate the module so the directory structure must match the name. An example of a role file would be:

NUCLEAR_ROLE(
# Some global modules that are useful
extension::FileWatcher
support::logging::ConsoleLogHandler
# Input from USB3 Cameras
input::Camera
)

This role file would create an executable with the modules module::extension::FileWatcher, module::support::logging::ConsoleLogHandler and module::input::Camera. This file is a CMake file so you are able to use # to declare comments.

NBS Files

NBS files are NUClear Binary Stream files. To make it easier to serialise streams of messages for storage sharing and playback, NUClear Roles defines a format for serialising messages to files. This format is based on the Neutron messaging system and NUClear's networking protocol. An nbs file has the following frames repeated continuously:

NameTypeDescription
headerchar[3]the header sequence 0xE2, 0x98, 0xA2 (the radioactive symbol ☢ in UTF-8)
sizeuint32the size of the frame after this byte in bytes
timestampuint64the timestamp of this frame in microseconds. Does not have to be a UTC timestamp.
hashuint64a 64 bit hash that identifies the type of the message
payloadchar*the serialised payload bytes

All values within this format are little endian.

An .nbz or .nbs.gz file is a compressed nbs file using gzip.

NBS files can have an associated index file. This allows for quicker random access to the coresponding nbs file. An .nbs.idx file has the following frames, each compressed with gzip, repeated continuously:

NameTypeDescription
hashuint64The 64-bit xxhash for the payload type
subtypeuint32The id of the message if it exists, otherwise 0
timestampuint64The timestamp field of the message if it exists or the timestamp at which it was emitted in nanoseconds
offsetuint64Offset to start of the coresponding nbs frame, i.e. to just before the radiation symbol ☢
sizeuint32Size of the whole packet from the radiation symbol

All values within the index file are little endian.

Neutrons

Reactors emit data in the form of messages called Neutrons. Neutrons are Protobuf messages in a C++ wrapper. These are all located in the shared/message/ directory, and have the .proto extension. An example is WalkCommand.proto:

syntax = "proto3";
package message.motion;
import "Vector.proto";
message WalkCommand {
uint64 subsumptionId = 1; // reservation identifier for servo control
vec3 command = 2; // x and y are velocity in m/s and angle is in rads/s
}

Examples

These examples use links to specific commits in the NUbots GitHub repository. They are likely out of date and don't reflect the functionality in the current main branch. They are intended to be used as examples to help understand the NUClear framework.

On Statements

Looking at SensorFilter.cpp we can see some examples of NUClear on statements.

The first on statement is located at line 94 of SensorFilter.cpp.

on<Configuration>("SensorFilter.yaml").then([this](const Configuration& config) {
log_level = cfg["log_level"].as<NUClear::LogLevel>();
// Button config
config.buttons.debounceThreshold = cfg["buttons"]["debounce_threshold"].as<int>();
...
});

The DSL request is on<Configuration>. This means the runtime argument here is ("SensorFilter.yaml"). This is the configuration file. The callback is

then([this](const Configuration& config) {
log_level = cfg["log_level"].as<NUClear::LogLevel>();
// Button config
config.buttons.debounceThreshold = cfg["buttons"]["debounce_threshold"].as<int>();
...
});

The const Configuration& config is a parameter of type Configuration. We can see examples of how this type works in the lines after it. cfg["buttons"]["debounce_threshold"].as<int>() finds the value labelled as ["buttons"]["debounce_threshold"] in the configuration file and retrieves it as an int type.

This value is then stored in the member variable debounceThreshold in the struct buttons.

This reaction is used at startup to set many variables from a configuration file. The next on statement does this as well, but with the FootDownNetwork.yaml configuration file.

The third on statement uses the DSL words Last, Trigger, With and Single.

on<Last<20, Trigger<RawSensors>>, With<KinematicsModel>, Single>().then(
[this](const std::list<std::shared_ptr<const RawSensors>>& sensors, const KinematicsModel& model) {
...
});

The DSL request is on<Last<20, Trigger<RawSensors>>, With<KinematicsModel>, Single>. This says that we will create a task for this reaction when we receive a RawSensors message. The last 20 received RawSensors messages will be stored in a std::list. With<KinematicsModel> will get the last available KinematicsModel message. The KinematicsModel message is emitted once on<Configuration> in the KinematicsConfiguration module to provide measurements for the robot. Finally, the Single word is used to only run one task for this reaction at any given time. If a RawSensors message is received while a task is already running, a new task will not be created.

None of the words used require runtime arguments, so we do not have any here. The callback is

then(
[this](const std::list<std::shared_ptr<const RawSensors>>& sensors, const KinematicsModel& model) {
...
});

The first parameter for this lambda statement is a std::list. This is because the word Last is used. The list will contain those last 20 received messages as specified in the DSL request. It is also valid to use a std::vector for this parameter. The KinematicsModel parameter is not a list because Last only applies to the message in the Trigger.

The next on statement in SensorFilter.cpp uses Trigger, Optional, With, Single, and Priority.

update_loop =
on<Trigger<RawSensors>, Optional<With<Sensors>>, With<KinematicsModel>, Single, Priority::HIGH>()
.then(
"Main Sensors Loop",
[this](const RawSensors& input,
const std::shared_ptr<const Sensors>& previousSensors,
const KinematicsModel& kinematicsModel) {
auto sensors = std::make_unique<Sensors>();
...
});

The DSL request is on<Trigger<RawSensors>, Optional<With<Sensors>>, With<KinematicsModel>, Single, Priority::HIGH>. This will create a task when RawSensors and KinematicsModel messages are received. We do not need to have received a Sensors message since it is Optional. If a task is already running, a new task will not be created since the Single word is present. Priority::HIGH specifies that the PowerPlant should give this a HIGH priority when scheduling.

Another aspect of this reactor is the update_loop variable. This is a ReactionHandle type and can be found in the header file. The reaction can be enabled by calling update_loop.enable() and disabled by calling update_loop.disable().

As expected, our callback has const RawSensors& input and const KinematicsModel& kinematicsModel since we asked for the RawSensors and the KinematicsModel messages. The interesting part of this is the std::shared_ptr<const Sensors> previousSensors. This will either be a nullptr or a valid Sensors message. There are checks in the function to see if the pointer is null and this determines how the function behaves.

Looking at line 133 of ScriptTuner.cpp we can see an example of an on<IO> reaction.

on<IO>(STDIN_FILENO, IO::READ).then([this] {
// Get the character the user has typed
switch (getch()) {
...
}
// Update whatever visual changes we made
refreshView();
});

In this case the DSL request is on<IO> and the runtime arguments are (STDIN_FILENO, IO::READ) which directs the PowerPlant to monitor for new data to read on the standard input file (i.e. the keybaord). Finally, the callback is

then([this] {
// Get the character the user has typed
switch (getch()) {
...
}
// Update whatever visual changes we made
refreshView();
});

Emit Statements

An example of local emission can be seen in SensorFilter.cpp where we call

emit(std::move(sensors));

This emits a Sensors message. This can then be received by reactors waiting for a Sensors message to trigger the reaction.

Looking at line 236 of GameController.cpp, we can see an example of NUClear network emission.

powerplant.emit_shared<Scope::NETWORK>(std::move(gameState), "nusight", true);

This tells the PowerPlant to emit something across the network. In this case, we are emitting gameState, which is a GameState message. The target is nusight, signifying that it will be received by NUsight. true signifies that it is reliable.

Looking at line 112 of ScriptTuner.cpp, we can see an example of an INITIALIZE scoped emit statement.

emit<Scope::INITIALIZE>(std::make_unique<RegisterAction>(RegisterAction{
id,
"Script Tuner",
{std::pair<float, std::set<LimbID>>(
1, {LimbID::LEFT_LEG, LimbID::RIGHT_LEG, LimbID::LEFT_ARM, LimbID::RIGHT_ARM, LimbID::HEAD})},
[this](const std::set<LimbID>&) {},
[this](const std::set<LimbID>&) {},
[this](const std::set<ServoID>&) {}}));

This tells the PowerPlant to emit something at system initialization. In this case, we are emitting a RegisterAction which registers the ScriptTuner module with the subsumption system.

NUbots acknowledges the traditional custodians of the lands within our footprint areas: Awabakal, Darkinjung, Biripai, Worimi, Wonnarua, and Eora Nations. We acknowledge that our laboratory is situated on unceded Pambalong land. We pay respect to the wisdom of our Elders past and present.
Copyright © 2024 NUbots - CC-BY-4.0
Deploys by Netlify