Skip to content

ZilantRobotics/cyphal_communicator

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

85 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

Cyphal communicator

Cyphal communicator is a ROS package that connects the Cyphal HITL autopilot interface and a simulator interface (based on ROS, ArduPilot JSON, etc).

Purpose

The Cyphal communicator is primailry intended for ArduPilot/PX4 Cyphal HITL simulation, but it can be used for other purposes as well.

Minimal technical requirements

  • Communicator node: ROS-noetic, ubuntu 20.04
  • Autopilot hardware: CUAV V5+
  • CAN-sniffer: handle at least 2500 CAN frames/sec

Content

1. Communicator Cyphal and ROS Interfaces

Cyphal interface on the communicator node can be illustrated with Yukon gui tool as shown below:

drawing

Here green topics are publishers, red topics are subscribers, gray topics are RPC-services.

1.1. Minimal quadcopter interface

The following Cyphal interface is supported for a minimal quadrotor application:

1. Actuator

Cyphal interface:

Interface Communicator's Port Message
udral/actuator sub.setpoint
sub.readiness
pub.feedback
udral.service.actuator.common.sp.Vector31
reg.udral.service.common.Readiness
zubax.telega.CompactFeedback

ROS-interface for necessary setpoint and readiness:

flowchart LR

setpoint[ setpoint, reg.udral.service.actuator.common.sp.Vector8] --> F(SetpointCyphalToRos) --> actuators_raw[ /uav/actuators_raw, sensor_msgs/Joy]
readiness[ readiness, reg.udral.service.common.Readiness] --> R(ReadinessCyphalToRos) --> arm[ /uav/arm, std_msgs::Bool]
Loading

ROS-interface for auxilliary ESC feedback:

flowchart LR
esc_status[ /uav/esc_status, mavros_msgs/ESCTelemetryItem] --> EscStatusRosToCyphal(EscStatusRosToCyphal)
EscStatusRosToCyphal --> esc_feedback_0[ esc_feedback_0, zubax.telega.CompactFeedback]
EscStatusRosToCyphal --> esc_feedback_n[ ...]
EscStatusRosToCyphal --> esc_feedback_7[ esc_feedback_7, zubax.telega.CompactFeedback]
Loading

2. IMU

Cyphal interface:

Interface Communicator's Port Message
imu pub.accelerometer
pub.gyro
uavcan.si.sample.acceleration.Vector3
uavcan.si.sample.angular_velocity.Vector3

ROS-interface:

flowchart LR

imu[ /uav/imu, sensor_msgs/Imu] --> F(ImuRosToCyphal)
F(ImuRosToCyphal) --> gyro[ gyro, uavcan.si.sample.angular_velocity.Vector3]
F(ImuRosToCyphal) --> accel[ accel, uavcan.si.sample.acceleration.Vector3]
Loading

3. Magnetometer

Cyphal interface:

Interface Communicator's Port Message
Magnetometer pub.mag uavcan.si.sample.magnetic_field_strength.Vector3

ROS-interface:

flowchart LR

imu[ /uav/mag, sensor_msgs/MagneticField] --> F(MagRosToCyphal) --> mag[ mag, uavcan.si.sample.magnetic_field_strength.Vector3]
Loading

4. Barometer

Cyphal interface:

Interface Communicator's Port Message
Barometer pub.pressure
pub.temperature
uavcan.si.sample.pressure.Scalar
uavcan.si.sample.temperature.Scalar

ROS-interface:

flowchart LR

static_temperature[ /uav/static_temperature, std_msgs/Float32] --> BaroRosToCyphal(BaroRosToCyphal) --> baro_temperature[ baro_temperature, uavcan.si.sample.temperature.Scalar]

static_pressure[ /uav/static_pressure, std_msgs/Float32] --> BaroRosToCyphal --> baro_pressure[ baro_pressure, uavcan.si.sample.pressure.Scalar]
Loading

5. GNSS

Cyphal interface:

Interface Communicator's Port Message
udral/gnss pub.point
pub.status
pub.sats
pub.pdop
reg.udral.physics.kinematics.geodetic.PointStateVarTs
uavcan.primitive.scalar.Integer16
uavcan.primitive.scalar.Integer16
uavcan.primitive.scalar.Integer16

ROS-interface:

flowchart LR
yaw[ /uav/yaw, std_msgs/Float32] --> GpsRosToCyphal(GpsRosToCyphal) --> gps_yaw[ gps_yaw, uavcan.si.sample.angle.Scalar]

point[ /uav/gps_point, sensor_msgs/NavSatFix] --> GpsRosToCyphal
GpsRosToCyphal --> gps_status[ gps_status, uavcan.primitive.scalar.Integer16]
GpsRosToCyphal --> gps_point[ gps_point, reg.udral.physics.kinematics.geodetic.PointStateVarTs]

velocity[ /uav/velocity, geometry_msgs/Twist] --> GpsRosToCyphal --> gps_point[ gps_point, reg.udral.physics.kinematics.geodetic.PointStateVarTs]

GpsRosToCyphal --> gps_sats[ gps_sats, uavcan.primitive.scalar.Integer16]
GpsRosToCyphal --> gps_pdop[ gps_pdop, uavcan.primitive.scalar.Integer16]
Loading

1.2. Extended interface

The following Cyphal allows to run VTOL application and add a few auxilliary features:

6. RGB LED

Cyphal interface:

Interface Communicator's Port Message
Udral/rgbled sub.rgbled reg.udral.physics.optics.HighColor

ROS-interface not supported yet

7. Airspeed (including Differential Pressure)

Cyphal interface:

Interface Communicator's Port Message
udral/airspeed pub.aspd.cas
pub.aspd.tas
pub.aspd.dpres
pub.aspd.temperature
uavcan.si.sample.velocity.Scalar
uavcan.si.sample.velocity.Scalar
uavcan.si.sample.pressure.Scalar
uavcan.si.sample.temperature.Scalar

ROS-interface for Airspeed:

flowchart LR
tas[ /uav/airspeed/tas, std_msgs/Float32] --> AirspeedRosToCyphal(AirspeedRosToCyphal)
cas[ /uav/airspeed/cas, std_msgs/Float32] --> AirspeedRosToCyphal(AirspeedRosToCyphal)
cas[ /uav/static_temperature, std_msgs/Float32] --> AirspeedRosToCyphal(AirspeedRosToCyphal)
AirspeedRosToCyphal --> aspd_tas[ aspd.tas, uavcan.si.sample.velocity.Scalar]
AirspeedRosToCyphal --> aspd_cas[ aspd.cas, uavcan.si.sample.velocity.Scalar]
AirspeedRosToCyphal --> aspd_temp[ aspd.temp, uavcan.si.sample.temperature.Scalar]
Loading

ROS-interface for Differential Pressure:

flowchart LR
dpres[ /uav/raw_air_data, std_msgs/Float32] --> DiffPressureRosToCyphal(DiffPressureRosToCyphal)
DiffPressureRosToCyphal --> aspd_dpres[ aspd.dpres, uavcan.si.sample.pressure.Scalar]
Loading

8. Battery

Cyphal interface:

Interface Communicator's Port Message Rate
Udral/Battery pub.energy_source
pub.battery_status
pub.battery_parameters
reg.udral.physics.electricity.SourceTs
reg.udral.service.battery.Status
reg.udral.service.battery.Parameters
1...100
~1
~0.2

ROS-interface:

flowchart LR
battery[ /uav/battery, sensor_msgs/BatteryState] --> BatteryRosToCyphal(BatteryRosToCyphal)
BatteryRosToCyphal --> energy_source[ energy_source, reg.udral.physics.electricity.SourceTs]
BatteryRosToCyphal --> battery_status[ battery_status, reg.udral.service.battery.Status]
BatteryRosToCyphal --> battery_parameters[ battery_parameters, reg.udral.service.battery.Parameters]
Loading

9. Rangefinder

Cyphal interface:

Interface Communicator's Port Message Rate
Rangefinder pub.range uavcan.si.sample.length.Scalar

ROS-interface:

flowchart LR
tas[ /uav/height, std_msgs/Float32] --> RangefinderRosToCyphal(RangefinderRosToCyphal)
RangefinderRosToCyphal --> aspd_tas[ aspd.tas, uavcan.si.sample.length.Scalar]
Loading

2. PX4 Cyphal interface

The actual Cyphal interface on the PX4 node configured in VTOL octoplane coaxial can be illustrated with Yukon gui tool:

drawing

Here green topics are publishers, red topics are subscribers, gray topics are RPC-services. A few topics disabled topics are not shown to make an image more compact.

1. Actuator

Cyphal interface:

Interface PX4's Port Message
udral/actuator pub.udral.esc.0
pub.udral.readiness.0
sub.udral.feedback.0
...
sub.udral.feedback.7
udral.service.actuator.common.sp.Vector31
reg.udral.service.common.Readiness

zubax.telega.CompactFeedback
.

Related PX4 parameters:

Name Description
UCAN1_ESC_PUB Cyphal ESC publication port ID
UCAN1_READ_PUB Cyphal ESC readiness publication port ID
UCAN1_FB0_SUB Cyphal ESC 0 zubax feedback port ID
... ...
UCAN1_FB7_SUB Cyphal ESC 7 zubax feedback port ID

On PX4 side actuators logic is implemented within UavcanEscController, ReadinessPublisher and UavcanEscFeedbackSubscriber drivers.

2. IMU

Cyphal interface:

Interface PX4's Port Message
imu sub.udral.imu.0
sub.udral.imu.accel.0
sub.udral.imu.gyro.0
uavcan.primitive.array.Real16.1.0
uavcan.si.sample.acceleration.Vector3
uavcan.si.sample.angular_velocity.Vector3

Related PX4 parameters:

Name Description
UCAN1_IMU_SUB Udral IMU 0 subscription port ID
UCAN1_ACCEL_SUB Udral Accelerometer 0 subscription port ID
UCAN1_GYRO_SUB Udral Gyroscope 0 subscription port ID

On PX4 side IMU logic is implemented within UavcanAccelerometerSubscriber and UavcanGyroscopeSubscriber drivers.

3. Magnetometer

Cyphal interface:

Interface Communicator's Port Message
Magnetometer sub.udral.mag.0 uavcan.si.sample.magnetic_field_strength.Vector3

Related PX4 parameters:

Name Description
UCAN1_MAG_SUB Udral Magnetometer 0 subscription port ID

On PX4 side IMU logic is implemented within UavcanMagnetometerSubscriber driver.

4. Barometer

Cyphal interface:

Interface Communicator's Port Message
Barometer sub.baro.pressure.0
sub.baro.temperature.0
uavcan.si.sample.pressure.Scalar
uavcan.si.sample.temperature.Scalar

Related PX4 parameters:

Name Description
UCAN1_BAROP0_SUB Barometer 0 pressure subscription ID
UCAN1_BAROT0_SUB Barometer 0 temperature subscription ID

On PX4 side IMU logic is implemented within UavcanBarometerSubscriber driver.

5. GNSS

Cyphal interface:

Interface Communicator's Port Message
udral/gnss sub.gps.point.0
sub.gps.status.0
sub.gps.sats.0
sub.gps.pdop.0
reg.udral.physics.kinematics.geodetic.PointStateVarTs
uavcan.primitive.scalar.Integer16
uavcan.primitive.scalar.Integer16
uavcan.primitive.scalar.Integer16

Related PX4 parameters:

Name Description
UCAN1_GPS0_SUB GPS 0 subscription port ID
UCAN1_GPSPD0_SUB GPS 0 pdop subscription port ID
UCAN1_GPSSA0_SUB GPS 0 sats subscription port ID
UCAN1_GPSST0_SUB GPS 0 status subscription port ID

On PX4 side GNSS logic is implemented within UavcanGnssSubscriber driver.

6. RGB LED

Cyphal interface:

Interface Communicator's Port Message
Udral/rgbled pub.udral.rgbled.0 reg.udral.physics.optics.HighColor

Related PX4 parameters:

Name Description
UCAN1_RGBLED_PUB Cyphal RGB Controller port ID

On PX4 side RGB LED logic is implemented within RGBControllerPublisher driver.

7. Airspeed (including Differential Pressure)

Cyphal interface:

Interface Communicator's Port Message
udral/airspeed sub.udral.aspd.cas.0
sub.udral.aspd.tas.0
sub.udral.aspd.dpres.0
sub.udral.aspd.temperature.0
uavcan.si.sample.velocity.Scalar
uavcan.si.sample.velocity.Scalar
uavcan.si.sample.pressure.Scalar
uavcan.si.sample.temperature.Scalar
Name Description
UCAN1_ATAS0_SUB Udral Airspeed TAS 0 subscription port ID
UCAN1_ACAS0_SUB Udral Airspeed CAS 0 subscription port ID
UCAN1_ATEM0_SUB Udral Airspeed Temperature 0 subscription port ID

On PX4 side Airspeed logic is implemented within UavcanAirspeedSubscriber driver.

Name Description
UCAN1_DPRES0_SUB UDRAL Differential pressure 0 subscription ID
UCAN1_DPRES1_SUB UDRAL Differential pressure 0 subscription ID

On PX4 side Differential Pressure logic is implemented within UavcanDiffPressureSubscriber driver.

8. Battery

Cyphal interface:

Interface Communicator's Port Message Rate
Udral/Battery sub.udral.energy_source.0
sub.udral.battery_status.0
sub.udral.battery_parameters.0
reg.udral.physics.electricity.SourceTs
reg.udral.service.battery.Status
reg.udral.service.battery.Parameters
1...100
~1
~0.2

Related PX4 parameters:

Name Description
UCAN1_BMS_BP_SUB UDRAL battery paramteters source subscription ID
UCAN1_BMS_BS_SUB UDRAL battery status source subscription ID
UCAN1_BMS_ESC_SUB UDRAL battery energy source subscription ID

On PX4 side Battery logic is implemented within UavcanBmsSubscriber driver.

9. Rangefinder

Cyphal interface:

Interface PX4's Port Message
Rangefinder sub.udral.range.0 uavcan.si.sample.length.Scalar

On PX4 side Rangefinder logic is implemented within RangefinderSubscriber driver.

3. Design

The package is designed to support a new type of simulator or autopilot interface just in case.

It has an autopilot interface that is represented with Cyphal HITL at the moment. It supports both PX4 and ArduPilot.

It has ROS (noetic) interface for UAV HITL simulator. It is suitable for PX4 (mainly mainteined) and ArduPilot (not well tested though).

In the main file, the application converts data from one interface to another and vice versa.

The structural relationship between the interfaces is shown in the figure below:

+-------+-------+-------+-------+-------+-------+-------+------+------+
|          Application entry point (src/main.c) .cfile                |
+-------+-------+-------+-------+-------+-------+-------+------+------+
           |                                    |
+------+-------+------+   +------+-------+------+-------+-------+-----+
| Autopilot interface |   |            Simulator interface            |
+------+-------+------+   +------+-------+------+-------+-------+-----+
           |                         |                      |
+------+-------+------+   +------+------+------+   +--------+---------+
|     Cyphal HITL     |   |   ROS interface    |   |    AP_JSON       |
| autopilot interface |   | UAV HITL simulator |   |     Gazebo       |
| (PX4 and ArduPilot) |   |  (PX4/ArduPilot)   |   | (ArduPilot only) |
+------+-------+------+   +------+------+------+   +--------+---------+

AP_JSON interface is not supported at the moment.

It is considered to migrate on ROS 2 later, so a new simulator interface may appear.

4. Redundancy

Cyphal/CAN communication allows to provide a few options of redundancy implementation.

Firstly, it allows multiple instances of sensors to be used. While the number of UART/I2C sensors connected to an autopilot is limited by the number of physical connectors on the autopilot, you are free to use multiple sensors on the CAN-bus: 2 GNSS sensors, 2 airspeed sensors, multiple rangefinders and navigation lights distributed around the vehicle and controlled by the autopilot - these are perfectly fine.

At the moment, the cyphal communicator and the custom branch of PX4-Autopilot supports 2 airspeed (differential pressure) sensors to demonstate this possibility and test it. You are free to extend it by adding an additional subject.

Secondly, redundancy can be provided by designing an UAV with more motors than the minimum required for flight. If one motor fails, the remaining motors can compensate for the loss of thrust, allowing the vehicle to maintain stability and control. One common approach is to build a hexacopter (six motors) or an octocopter (eight motors) instead of a quadcopter (four motors). With additional motors, the quadcopter can continue to fly even if one or more motors fail.

At the moment, Cyphal communicator as well as Cyphal/UDRAL are limited by 31 motors, though this number can be increased by using an additional control group or extending UDRAL specification. PX4 are limited by 16 motors, that is enough for most of the applications.

As an example, HITL simulator supports octocopter airframe to demostrate this possibility.

Thirdly, the redundancy can be provided by using an additional physical interface (transport layer). It can be second or third CAN-bus, or even another interface such as Cyphal/Serial or Cyphal/UDP.

The cyphal communicator allows to use multiple interfaces. By default it is based on vitual CAN-interface with name slcan0. You can specify another number of the interface and run an additional instance. PX4 capabilities are based on the specific hardware, but modern versions of the hardware typically have 2 CAN-buses.

5. Installation

Before running the communicator, you need to do 3 things:

  1. Create virtual CAN. It is expected that you are using CAN-sniffer device such as UAVCAN sniffer and programmer. An example of script that creates SLCAN is scripts/create_slcan.sh. This script automatically detect a connected device and create slcan0 port. You should create virtual CAN once after each sniffer connection to your PC.
  2. Configure environment variables. This step is required for setting subjects port id and few pathes. As an example, you can run source scripts/config.sh. You should call this script in each shell session.

After these steps you are able to run the communicator.

6. Running

You should connect a CAN-sniffer to an autopilot as shown below:

You should create slcan0.

Then run the communicator using the launch file:

roslaunch cyphal_communicator cyphal_communicator.launch

7. Usage example

Below you can see an example of using the cyphal_communicator in conjunction with a VTOL dynamics simulator.

vtol HITL dynamics simulator

8. LICENSE

The Cyphal Communicator project is licensed under the GNU General Public License, version 3

About

No description, website, or topics provided.

Resources

License

Stars

Watchers

Forks

Packages

No packages published

Languages