107-Arduino-Cyphal: Bringing Cyphal to Arduino

Breaking News: 107-Arduino-Cyphal v3.0.0 w/ modern API and full Cyphal compliance has just been released!

This release represents a significant overhaul of the entire library. As a result, it is possible to create a fully Cyphal-compliant application by leveraging a powerful, compact, and concise API. These are the main characteristics:

  • ROS/ROS2 style API with type erasure for creating Publisher's, Subscriptions's, ServiceServer's and ServiceClient's.

  • Run-time configurable parameters, such as

  • The library is free of Microcontroller/Arduino specific idioms, the library therefore compiles for any architecture (incl. your PC):

  • nunavut pre-generated C++ headers.

  • Support for both CAN and CAN FD PHY layers.

  • Implementation of the Register API supporting both RO and RW registers, as well as array and scalar types.

  • Implementation of the NodeInfo API for providing generic node information for i.e. yakut.

  • Provision of a uavcan/node/port/List.1.0 publisher which periodically publishes information on publisher and subscribed topics, as well as service servers and clients.

  • Self-explaining examples for Publisher, Subscriptions, ServiceServer and ServiceClient.

  • A number of full Cyphal compliant reference implementations.

  • There are also external support libraries that provide Cyphal-specific key functionality:

    • 107-Arduino-UniqueId provides a 16-Byte unique id over various Arduino platforms. This is needed for the NodeInfo API.
    • 107-Arduino-CriticalSection provides RAII-style critical sections for preventing race conditions when calling library APIs within both interrupts and normal execution context.

Let’s take a closer look at each of these features:

Declaration/Usage of a Cyphal-Node

The basic API entry point is a Node class instance, which must be provided with heap as well as a function pointer to a CAN transmit function:

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });

Processing happens inside spinSome which needs to be called regularly:

void loop()
{
  /* Process all pending OpenCyphal actions. */
  {
    CriticalSection crit_sec;
    node_hdl.spinSome();
  }
  /* ... */

Received CAN frames are passed to the application via onCanFrameReceived:

void onReceiveBufferFull(CanardFrame const & frame)
{
  node_hdl.onCanFrameReceived(frame);
}

Publisher

A Publisher can be created using the create_publisher API:

/* Create a publisher with a fixed port id: */
const auto heartbeat_pub = node_hdl.create_publisher<uavcan::node::Heartbeat_1_0>
  (1*1000*1000UL /* = transmit timeout / usec */);

/* Create a publisher with a custom port id: */
CanardPortID const ANGLE_ID = 1001U;
const auto angle_pub = node_hdl.create_publisher<uavcan::si::unit::angle::Scalar_1_0>
  (ANGLE_ID, 1*1000*1000UL /* = transmit timeout / usec */);

which can then be used to publish messages:

uavcan::node::Heartbeat_1_0 msg;

msg.uptime = now / 1000;
msg.health.value = uavcan::node::Health_1_0::NOMINAL;
msg.mode.value = uavcan::node::Mode_1_0::OPERATIONAL;
msg.vendor_specific_status_code = 0;

heartbeat_pub->publish(msg);

or

uavcan::si::unit::angle::Scalar_1_0 angle_scalar;
angle_scalar.radian = (b_angle_deg - b_angle_offset_deg) * M_PI / 180.0f;
angle_pub->publish(angle_scalar);

Subscription

A Subscription can be created using the create_subscription API:

/* Create a subscription with a fixed port id: */
const auto heartbeat_subscription = node_hdl.create_subscription<Heartbeat_1_0>(onHeartbeat_1_0_Received);

/* Create a subscription with a custom port id: */
static CanardPortID const BIT_PORT_ID   = 1620U;
const auto bit_subscription = node_hdl.create_subscription<Bit_1_0>(BIT_PORT_ID, onBit_1_0_Received);

Upon reception of such a transfer the callback provided during creation of the Subscription object is invoked:

void onBit_1_0_Received(Bit_1_0 const & msg)
{
  if(msg.value)
    digitalWrite(LED_BUILTIN, HIGH);
  else
    digitalWrite(LED_BUILTIN, LOW);
}

Service Server

A ServiceServer can be created using the create_service_server API:

const auto ServiceServer execute_command_srv = node_hdl.create_service_server<ExecuteCommand::Request_1_1, ExecuteCommand::Response_1_1>(
  2*1000*1000UL,
  onExecuteCommand_1_1_Request_Received);

Upon reception of a service clients request the callback provided during creation of the ServiceServer object is invoked:

ExecuteCommand::Response_1_1 onExecuteCommand_1_1_Request_Received(ExecuteCommand::Request_1_1 const & req)
{
  ExecuteCommand::Response_1_1 rsp;

  if (req.command == 0xCAFE)
    rsp.status = ExecuteCommand::Response_1_1::STATUS_SUCCESS;
  else
    rsp.status = ExecuteCommand::Response_1_1::STATUS_NOT_AUTHORIZED;

  return rsp;
}

Service Client

A ServiceClient can be created using the create_service_client API:

const auto srv_client = node_hdl.create_service_client<ExecuteCommand::Request_1_1, ExecuteCommand::Response_1_1>(
  2*1000*1000UL,
  onExecuteCommand_1_1_Response_Received);

Send an asynchronous request:

/* Request some coffee. */
std::string const cmd_param("I want a double espresso with cream!");
ExecuteCommand::Request_1_1 req;
req.command = 0xCAFE;
std::copy_n(cmd_param.begin(),
            std::min(cmd_param.length(), req.parameter.capacity()),
            req.parameter.begin());

if (!srv_client->request(27 /* remote node id */, req))
  Serial.println("Coffee request failed.");

Upon reception of a service servers response the callback provided during creation of the ServiceClient object is invoked:

void onExecuteCommand_1_1_Response_Received(ExecuteCommand::Response_1_1 const & rsp)
{
  if (rsp.status == ExecuteCommand::Response_1_1::STATUS_SUCCESS)
    Serial.println("Coffee successfully retrieved");
  else
    Serial.println("Error when retrieving coffee");
}

Register API

The Register API enables node configuration:

/* R/W register value. */
CanardNodeID node_id = node_hdl.getNodeId();
CanardPortID counter_port_id = DEFAULT_COUNTER_PORT_ID;
uint16_t counter_update_period_ms = DEFAULT_COUNTER_UPDATE_PERIOD_ms;

/* Creating a registry. */
const auto node_registry = node_hdl.create_registry();

/* Creating RO and RW registers. */
const auto reg_ro_node_description             = node_registry->route ("cyphal.node.description", {true}, []() { return "basic-cyphal-node"; });
const auto reg_ro_pub_counter_type             = node_registry->route ("cyphal.pub.counter.type", {true}, []() { return "uavcan.primitive.scalar.Integer8.1.0"; });
const auto reg_rw_node_id                      = node_registry->expose("cyphal.node.id", {}, node_id);
const auto reg_rw_pub_counter_id               = node_registry->expose("cyphal.pub.counter.id", {}, counter_port_id);
const auto reg_rw_pub_counter_update_period_ms = node_registry->expose("cyphal.pub.counter.update_period_ms", {}, counter_update_period_ms);

NodeInfo API

The NodeInfo API provides relevant node information:

static auto node_info = node_hdl.create_node_info
(
  /* uavcan.node.Version.1.0 protocol_version */
  1, 0,
  /* uavcan.node.Version.1.0 hardware_version */
  1, 0,
  /* uavcan.node.Version.1.0 software_version */
  0, 1,
  /* saturated uint64 software_vcs_revision_id */
#ifdef CYPHAL_NODE_INFO_GIT_VERSION
  CYPHAL_NODE_INFO_GIT_VERSION,
#else
  0,
#endif
  /* saturated uint8[16] unique_id */
  OpenCyphalUniqueId(),
  /* saturated uint8[<=50] name */
  "107-systems.l3xz-leg-ctrl"
);

Note: This release contains many breaking changes. If you are a corporation needing help to upgrade your 107-Arduino-Cyphal based application feel free to reach out to me (e-mail).

CC @pavel.kirienko @scottdixon @generationmake

4 Likes