This Arduino library implements the Cyphal protocol (v1.0-beta) utilizing libcanard.
Note: For commercial support, customisation or contract development contact [email protected].
This library works for
- arduino-pico:
Raspberry Pi Pico
,Adafruit Feather RP2040
, ... ✔️
arduino-cli compile -b rp2040:rp2040:rpipico -v examples/OpenCyphal-Heartbeat-Publisher -u -p /dev/ttyACM0
- ArduinoCore-renesas:
Portenta C33
,Uno R4 WiFi
,Uno R4 Minima
, ... ✔️
arduino-cli compile -b arduino:renesas_portenta:portenta_c33 -v examples/OpenCyphal-Heartbeat-Publisher -u -p /dev/ttyACM0
- Host (x86/x64/...): Using the CMake build system this library can be cross-compiled to a static C++ library and linked against any C++ executable. This is possible because the code itself is pure C/C++ without and dependencies to the Arduino framework.
git clone https://github.com/107-systems/107-Arduino-Cyphal && cd 107-Arduino-Cyphal
mkdir build && cd build
cmake .. && make
or
cmake -DBUILD_EXAMPLES=ON .. && make
- CyphalPicoBase/CAN-firmware: Firmware for the CyphalPicoBase/CAN board.
- CyphalServoController12/CAN-firmware: Firmware for the CyphalServoController12/CAN board.
- l3xz-aux-ctrl-firmware: Firmware for the L3X-Z auxiliary controller (CyphalPicoBase/CAN).
- l3xz-leg-ctrl-firmware: Firmware for the L3X-Z leg controller (l3xz-leg-ctrl-hardware).
- l3xz-radiation-sensor-firmware: Firmware for the L3X-Z radiation sensor (CyphalPicoBase/CAN).
- l3xz-pressure-sensor-firmware: Firmware for the L3X-Z pressure sensor (CyphalPicoBase/CAN).
#include <107-Arduino-Cyphal.h>
/* ... */
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { /* ... */ });
cyphal::Publisher<Heartbeat_1_0> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0>
(1*1000*1000UL /* = 1 sec in usecs. */);
/* ... */
void loop() {
/* Process all pending OpenCyphal actions. */
node_hdl.spinSome();
/* ... */
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);
/* ... */
}
#include <107-Arduino-Cyphal.h>
/* ... */
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { /* ... */ });
cyphal::Subscription heartbeat_subscription = node_hdl.create_subscription<Heartbeat_1_0>(onHeartbeat_1_0_Received);
/* ... */
void loop() {
/* Process all pending OpenCyphal actions. */
node_hdl.spinSome();
}
/* ... */
void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg)
{
char msg_buf[64];
snprintf(msg_buf, sizeof(msg_buf),
"Uptime = %d, Health = %d, Mode = %d, VSSC = %d",
msg.uptime, msg.health.value, msg.mode.value, msg.vendor_specific_status_code);
Serial.println(msg_buf);
}
#include <107-Arduino-Cyphal.h>
/* ... */
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { /* ... */ });
cyphal::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);
/* ... */
void loop() {
/* Process all pending OpenCyphal actions. */
node_hdl.spinSome();
}
/* ... */
ExecuteCommand::Response_1_1 onExecuteCommand_1_1_Request_Received(ExecuteCommand::Request_1_1 const & req)
{
ExecuteCommand::Response_1_1 rsp;
rsp.status = ExecuteCommand::Response_1_1::STATUS_SUCCESS;
return rsp;
}
#include <107-Arduino-Cyphal.h>
/* ... */
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { /* ... */ });
cyphal::ServiceClient<ExecuteCommand::Request_1_1> srv_client = node_hdl.create_service_client<ExecuteCommand::Request_1_1, ExecuteCommand::Response_1_1>
(2*1000*1000UL, onExecuteCommand_1_1_Response_Received);
/* ... */
void setup() {
ExecuteCommand::Request_1_1 req;
req.command = 0xCAFE;
if (!srv_client->request(27 /* remote node id */, req))
Serial.println("Service request failed.");
}
void loop() {
/* Process all pending OpenCyphal actions. */
node_hdl.spinSome();
}
/* ... */
void onExecuteCommand_1_1_Response_Received(ExecuteCommand::Response_1_1 const & rsp)
{
if (rsp.status == ExecuteCommand::Response_1_1::STATUS_SUCCESS)
Serial.println("Response: Success");
else
Serial.println("Response: Error");
}