This driver implements support for Cyphal ESCs such as Myxa, Mini node, kotleta20 and other devices.
It supports the minimal required features for a Cyphal node: uavcan.node.Heartbeat.
It supports ESC service for up to 8 ESC:
- reg.udral.service.actuator.common.sp,
- reg.udral.service.common.Readiness,
- zubax.telega.CompactFeedback.
The driver does not provide support for features such as uavcan.node.GetInfo, Register interface and uavcan.node.port.List.
First, you need to upload an ArduPilot firmware to the FMU. In general, it should work with any version of ArduPilot that supports LUA. It has been tested with the latest stable version v4.4.4
. The easiest ways to upload the firmware are to use QGroundControl or MissionPlanner.
QGroundControl | MissionPlanner |
---|---|
Alternatively, you can manually build a binary and upload the firmware via cli. Here is an example for CUAVv5:
./waf list_boards
./waf configure --board CUAVv5
./waf copter
./waf --targets bin/arducopter --upload
This driver should be loaded by placing the lua script in the
APM/scripts
directory on the microSD card, which can be done either directly or via MAVFTP.
Copy directly | Using MAVFtp |
---|---|
The following parameters should be set to start the script and configure the CAN driver:
SCR_ENABLE | 1 | 1 means scripting is enabled, 0 means disabled |
CAN_D1_PROTOCOL | 10 | 10 means scripting |
CAN_P1_DRIVER | First driver | |
CAN_P1_BITRATE | 1000000 | Default bitrate for most of the applications |
Then the flight controller should be rebooted and parameters should be refreshed.
Some parameters appear only after setting other parameters, so you may need to reboot the autopilot a few times
Once Cyphal.lua
script is succesfully executed, a few Cyphal registers will appear in the parameters.
The autopilot node has the following Cyphal-related parameters:
CYP_ENABLE | 1 | 1 means Cyphal is enabled, 0 means disabled |
CYP_NODE_ID | 1-127 | Node identifier in Cyphal-network. Usually, 127 is reserved for debugging tools and 1 is used for an autopilot. |
CYP_TESTS | 0 | If set to 1, self tests will be runned at the beginning of the application. |
and it has the following Port-registers:
CYP_RD | 1-8191 | Readiness port id. Enabled if less then 8191, otherwise disabled. By default, 65535. |
CYP_SP | 1-8191 | Setpoint port id for ESCs. Enabled if less then 8191, otherwise disabled. By default, 65535. |
CYP_FB | 1-8191 | ESC Feedback array of port id. Enabled if less then 8191, otherwise disabled. By default, 65535. When enabled, it occupies 8 consecutive port identifiers. For example, if it is 3000, it will occupy [3000, 3007] identifiers. |
It's well researched, but sometimes parameters don't appear in the Ground Control Station. A simple reboot of QGC solves this problem.
Configure the yakut-related environment variables, connect autopilot and CAN-sniffer together.
If you run y mon
, you should get:
Here, we have 2 nodes: autopilot with node_id=1 (it is configured in CYP_NODE_ID
) and yakut with node_id=127. The autopilot publishes setpoint with port_id=2000 (CYP_SP
) with ~234 Hz and readiness with port_id=2001 (CYP_RD
) with ~10 Hz.
Since the node doesn't support anything except
uavcan.node.Heartbeat
, it doesn't have a name and registers are not avaliable via Cyphal/CAN interface.
Additionally, you can subscribes to the setpoint and readiness topics:
y sub 2001:reg.udral.service.common.Readiness
y sub 2000:reg.udral.service.actuator.common.sp.Vector8
in process
Before pushing a commit:
- Check code style with
lua-check
- Run tests with
lua tests/all.lua
Reference: https://opencyphal.org/specification/Cyphal_Specification.pdf
1. Insufficent memory loading
Try to disable some feature as it is recommended on the ardupilot forum.
For example, LOG_FILE_BUFSIZE = 8
can help.
2. Why Cyphal paramters are float?
Docs says all scripting defined parameters are of type FLOAT, ie floating point numbers
.