# 5. Cyphal PWM node
This page is about Cyphal related details such as interface, supported features, registers, configuration and usage examples and software versions. For general information please refer to the 1. General page, for hardware related details including wiring examples please refer to the uNode or Mini v2 pages.
# 5.1. Cyphal interface
This node interacts with the following data types:
Common for any node
№ | Type | Message |
---|---|---|
1 | pub | uavcan.node.Heartbeat (opens new window) |
2 | RPC-service | uavcan.node.GetInfo.Response (opens new window) |
3 | RPC-service | uavcan.node.ExecuteCommand (opens new window) |
4 | RPC-service | uavcan.register.List (opens new window) |
5 | RPC-service | uavcan.register.Access (opens new window) |
6 | pub (since hardware v3) | uavcan.node.port.List (opens new window) |
Here ExecuteCommand
supports COMMAND_RESTART
, COMMAND_FACTORY_RESET
and COMMAND_STORE_PERSISTENT_STATES
.
Electronic speed controller (ESC) service
This node supports the Electronic Speed Controller (ESC) service
according to the UDRAL standard (see for details) (opens new window). It uses the following subjects:
№ | Type | Message | Topic name |
---|---|---|---|
1 | subscriber | reg.udral.service.actuator.common.sp/* (opens new window) | setpoint |
2 | subscriber | reg.udral.service.common.Readiness.0.1 (opens new window) | readiness |
3 | publisher | reg.udral.service.actuator.common.Feedback.0.1 (opens new window) | feedback |
Circuit status service
Like any other RaccoonLab node, this node also supports the Circuit status service
. It uses the following subjects:
№ | Type | Message | Topic name |
---|---|---|---|
1 | pub | uavcan.si.sample.voltage.Scalar.1.0 | 5v |
2 | pub | uavcan.si.sample.voltage.Scalar.1.0 | vin |
3 | pub | uavcan.si.sample.temperature.Scalar.1.0 | dev_temp |
Since uNode doesn't have an internal DC-DC, it doesn't provide Vin voltage.
# 5.2. Cyphal Registers
№ | Register name | Note | Description |
---|---|---|---|
0 | id | reboot required | Node ID |
1 | control_mode | reboot required | Control mode (opens new window) |
2 | ttl_ms | Time to live (read about CONTROL_TIMEOUT here (opens new window)) | |
3 | pwm1_ch | Index of setpoint | |
4 | pwm1_min | PWM duration when setpoint is min. | |
5 | pwm1_max | PWM duration when setpoint is max. | |
6 | pwm1_def | PWM duration when setpoint is not present or device is not engaged. | |
7 | uavcan.pub.feedback1.id | Port identifier. | |
8 | uavcan.pub.feedback1.type | persistent | reg.udral.service.actuator.common.Feedback.0.1 |
9 | pwm2_ch | Index of setpoint | |
10 | pwm2_min | PWM duration when setpoint is min. | |
11 | pwm2_max | PWM duration when setpoint is max. | |
12 | pwm2_def | PWM duration when setpoint is not present or device is not engaged. | |
13 | uavcan.pub.feedback2.id | Port identifier. | |
14 | uavcan.pub.feedback2.type | persistent | reg.udral.service.actuator.common.Feedback.0.1 |
15 | pwm3_ch | Index of setpoint | |
16 | pwm3_min | PWM duration when setpoint is min. | |
17 | pwm3_max | PWM duration when setpoint is max. | |
18 | pwm3_def | PWM duration when setpoint is not present or device is not engaged. | |
19 | uavcan.pub.feedback3.id | Port identifier. | |
20 | uavcan.pub.feedback3.type | persistent | reg.udral.service.actuator.common.Feedback.0.1 |
21 | pwm4_ch | Index of setpoint | |
22 | pwm4_min | PWM duration when setpoint is min. | |
23 | pwm4_max | PWM duration when setpoint is max. | |
24 | pwm4_def | PWM duration when setpoint is not present or device is not engaged. | |
25 | uavcan.pub.feedback4.id | Port identifier. | |
26 | uavcan.pub.feedback4.type | persistent | reg.udral.service.actuator.common.Feedback.0.1 |
27 | uavcan.sub.readiness.id | reboot required | Port identifier |
28 | uavcan.sub.readiness.type | persistent | reg.udral.service.common.Readiness.0.1 |
29 | uavcan.sub.setpoint.id | reboot required | Port identifier |
30 | uavcan.sub.setpoint.type | persistent | reg.udral.service.actuator.common.sp.Vector4.0.1 |
31 | uavcan.pub.crct.5v.id | Port identifier | |
32 | uavcan.pub.crct.5v.type | persistent | uavcan.si.sample.voltage.Scalar.1.0 |
33 | uavcan.pub.crct.vin.id | Port identifier | |
34 | uavcan.pub.crct.vin.type | persistent | uavcan.si.sample.voltage.Scalar.1.0 |
35 | uavcan.pub.crct.temp.id | Port identifier | |
36 | uavcan.pub.crct.temp.type | persistent | uavcan.si.sample.temperature.Scalar.1.0 |
37 | name | reboot required | Node custom name |
Since uNode has only 2 channels,
pwm3
andpwm4
have no effect.
You can check examples of yaml files with registers for micro node (opens new window) and mini v2 node (opens new window).
# 5.3. Configuration
Before using in the real application, it is necessary to configure the device. It is recommended to use Yakut (opens new window) cli or Yukon (opens new window) gui.
Please note that for safety reasons, a node configuration should only be carried out with unarmed propellers!
Step 1. Connect the device
Connect the node via sniffer to your PC.
An example of the connection is shown below.
Step 2. Configure the environment
Typically you will need to:
- Configure all required environment variables
- Compile DSDL based on public regulated data types
- Create SLCAN based on CAN sniffer
Please refer to Yakut
and Yukon
documentation to understand how to do it.
Step 3. Monitor the node
Let's say, you have a Cyphal node correctly connected to a CAN sniffer.
The state of the node can be visualized using Yakut
. Run y mon
to see the node. The possible command output is:
Alternatively, you can use Yukon
. An example of monitor is shown below:
Step 4. Ports configuration
The minimum possible application requires the following ports to be configured:
readiness
,setpoint
.
Auxillary ports are:
crct.5v
,crct.temp
,crct.vin
,crct.feedback*
,
According to the specification (opens new window) the port IDs should be in the range [0, 6143]. Disabled subjects should have port id 65535.
A fully configured application might look like this:
You can subscribe to the topics to verify the result:
5v voltage | feedback |
---|---|
![]() | ![]() |
Step 5. Parameters configuration
The following parameters must be configured through the register interface:
id
,pwm*
registers,ttl_ms
,
The value of id
register must be unique within the network. It must be withing the range [1; 126].
The register value of ttl_ms
must be at least twice more than the setpoint period.
Since right now the setpoint type is Vector4, pwm*_ch
registers supports values from 0 to 3. Other values will configure the corresponded pwm pin to the default state. For ESC it is preferred to have min values as 1000, max value as 2000 and default as 1000. For servo these values might be anything within the range [1000, 2000]. It is up to up.
You may also want to configure the auxillary parameters:
name
.
Step 6. Control the node
After the configuration, you are able to send the setpoint to the device to verify that everything it was successful.
In general, you should engage the device by sending readiness command, and then send a setpoint.
Click here to show Yakut usage example
Let's say, you have configured registers.
First terminal session. Configure the Yakut environment variables and start to periodically send the readiness message to engage the device. Try the following script. Specify NODE_ID as your actual node ID.
#!/bin/bash
NODE_ID=51
REGISTER_BASE=uavcan.sub.readiness
PORT_ID=$(y r $NODE_ID $REGISTER_BASE.id)
DATA_TYPE=$(y r $NODE_ID $REGISTER_BASE.type | tr -d '"')
y pub -T 0.1 $PORT_ID:$DATA_TYPE 3
Another terminal session. Configure the Yakut environment variables and start to periodically send the setpoint command. Try the following script. Specify NODE_ID as your actual node ID and VALUE as desired value of setpoint withing range [0.0, 1.0]:
#!/bin/bash
NODE_ID=51
VALUE=0.1
REGISTER_BASE=uavcan.sub.setpoint
PORT_ID=$(y r $NODE_ID $REGISTER_BASE.id)
DATA_TYPE=$(y r $NODE_ID $REGISTER_BASE.type | tr -d '"')
y pub -T 0.05 $PORT_ID:$DATA_TYPE "[$VALUE, $VALUE, $VALUE, $VALUE]"
# 5.4. Ardupilot integration
Ardupilot doesn't officially support Cyphal (at the time of writing), so it is expected to use the custom cyphal branch of ardupilot (opens new window), since PR is not merged.
1. Port configuration
The following Ardupilot Cyphal registers should have the same port identifiers as GPS:
Port | Type |
---|---|
setpoint | reg.udral.service.actuator.common.sp/* (opens new window) |
readiness | reg.udral.service.common.Readiness.0.1 (opens new window) |
2. Channels configuration
3. Verification
# 5.5. PX4 integration
PX4 sends setpoint and readiness with following values:
- setpoint port ID is
uavcan.pub.esc.0.id
, - readiness port ID is
uavcan.pub.esc.0.id
+ 1.
These port identifiers of the autopilot should be the same as those of the node.
PX4 sends setpoint within the range [0; 8192]. So, you also need to configure control_mode
as 1.
# 5.6. Versions
Micro and mini v2 releases:
Version | Date | SHA | Link | Description |
---|---|---|---|---|
v1.2 | Feb 23, 2023 | b4e042b | link (opens new window) | Add port.List , add hardware version, extend git hash length to 64 bit, few fixes |
v1.1.2 | Nov 17, 2022 | 4f393f4 | - | Add control mode parameter to be compatible with PX4 |
v1.0.1 | Oct 23, 2022 | 47a71fd | link (opens new window) | Initial release |