12 changed files with 1 additions and 195 deletions
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
# This directory can be used for vendor specific DSDL for ArduPilot |
@ -1,8 +0,0 @@
@@ -1,8 +0,0 @@
|
||||
This directory contains the DSDL for the ArduPilot vendor specific |
||||
UAVCAN messages. |
||||
|
||||
For service messages we use IDs starting at 200 |
||||
|
||||
For non-service messages we use IDs starting at 20000 |
||||
|
||||
https://uavcan.org/Specification/5._Application_level_conventions/#id-distribution |
@ -1,36 +0,0 @@
@@ -1,36 +0,0 @@
|
||||
# |
||||
# Auxilary Single battery info. |
||||
# |
||||
# This message is to be used in conjunction with uavcan/equipment/power/1092.BatteryInfo.uavcan |
||||
|
||||
# Please ensure that this message is sent before the BatteryInfo which doesn't |
||||
# include the timestamp. The following fields should contain the timestamp of the last current measurement. |
||||
uavcan.Timestamp timestamp |
||||
|
||||
# Battery individual cell voltages |
||||
# length of following field also used as cell count |
||||
float16[<=255] voltage_cell # [Volt] |
||||
|
||||
# Number of Charge/Discharge Cycles |
||||
# A charge cycle is defined as a complete discharge and charge. |
||||
# IE when the system uses all of the battery's available energy capacity. |
||||
# Please note that this value doesn't mean that the cycle count should be incremented at every charge. |
||||
# For example, if half of a battery's charge is used in one run, |
||||
# and then recharged fully that is half of a cycle. If the same thing occurs again |
||||
# then the charge cycle count would be incremented once, not twice. |
||||
uint16 cycle_count |
||||
|
||||
# Number of times the battery was discharged over the rated capacity |
||||
uint16 over_discharge_count |
||||
|
||||
# Max instantaneous current draw since last message |
||||
float16 max_current # [Ampere] |
||||
|
||||
# Nominal voltage of the battery pack |
||||
# the nominal Voltage can be used for conversion between Wh and Ah |
||||
# if the value of this field is 0, the conversion should be omitted. |
||||
float16 nominal_voltage # [Volt] |
||||
|
||||
bool is_powering_off # Power off event imminent indication, false if unknown |
||||
|
||||
uint8 battery_id # Identifies the battery within this vehicle, e.g. 0 - primary battery |
@ -1,68 +0,0 @@
@@ -1,68 +0,0 @@
|
||||
# Network-synchronized timestamp, 0 if not available. Note: not necessarily a UTC time. |
||||
uavcan.Timestamp timestamp |
||||
|
||||
# icao address |
||||
uint32 icao_address |
||||
|
||||
# Time since last communication in seconds |
||||
uint16 tslc |
||||
|
||||
# Traffic position in lat-lon-alt. Check alt_type for altitude datum |
||||
int32 latitude_deg_1e7 |
||||
int32 longitude_deg_1e7 |
||||
float32 alt_m |
||||
|
||||
# Traffic heading in radians. |
||||
# Course over ground if heading is unavailable. 0 if neither are available. |
||||
float16 heading |
||||
|
||||
# Traffic velocity in m/s |
||||
float16[3] velocity |
||||
|
||||
# Traffic squawk code |
||||
uint16 squawk |
||||
|
||||
# Traffic callsign |
||||
uint8[9] callsign |
||||
|
||||
# Traffic source |
||||
uint3 SOURCE_ADSB = 0 |
||||
uint3 SOURCE_ADSB_UAT = 1 |
||||
uint3 SOURCE_FLARM = 2 |
||||
uint3 source |
||||
|
||||
# Traffic type |
||||
uint5 TRAFFIC_TYPE_UNKNOWN = 0 |
||||
uint5 TRAFFIC_TYPE_LIGHT = 1 |
||||
uint5 TRAFFIC_TYPE_SMALL = 2 |
||||
uint5 TRAFFIC_TYPE_LARGE = 3 |
||||
uint5 TRAFFIC_TYPE_HIGH_VORTEX_LARGE = 4 |
||||
uint5 TRAFFIC_TYPE_HEAVY = 5 |
||||
uint5 TRAFFIC_TYPE_HIGHLY_MANUV = 6 |
||||
uint5 TRAFFIC_TYPE_ROTOCRAFT = 7 |
||||
uint5 TRAFFIC_TYPE_GLIDER = 9 |
||||
uint5 TRAFFIC_TYPE_LIGHTER_THAN_AIR = 10 |
||||
uint5 TRAFFIC_TYPE_PARACHUTE = 11 |
||||
uint5 TRAFFIC_TYPE_ULTRA_LIGHT = 12 |
||||
uint5 TRAFFIC_TYPE_UAV = 14 |
||||
uint5 TRAFFIC_TYPE_SPACE = 15 |
||||
uint5 TRAFFIC_TYPE_EMERGENCY_SURFACE = 17 |
||||
uint5 TRAFFIC_TYPE_SERVICE_SURFACE = 18 |
||||
uint5 TRAFFIC_TYPE_POINT_OBSTACLE = 19 |
||||
uint5 traffic_type |
||||
|
||||
# Altitude type |
||||
uint7 ALT_TYPE_ALT_UNKNOWN = 0 |
||||
uint7 ALT_TYPE_PRESSURE_AMSL = 1 |
||||
uint7 ALT_TYPE_WGS84 = 2 |
||||
uint7 alt_type |
||||
|
||||
# Validity flags |
||||
bool lat_lon_valid |
||||
bool heading_valid |
||||
bool velocity_valid |
||||
bool callsign_valid |
||||
bool ident_valid |
||||
bool simulated_report |
||||
bool vertical_velocity_valid |
||||
bool baro_valid |
@ -1,5 +0,0 @@
@@ -1,5 +0,0 @@
|
||||
bool heading_valid |
||||
bool heading_accuracy_valid |
||||
|
||||
float16 heading_rad |
||||
float16 heading_accuracy_rad |
@ -1,10 +0,0 @@
@@ -1,10 +0,0 @@
|
||||
# Node specific GNSS error codes, primarily available for logging and diagnostics |
||||
uint32 error_codes |
||||
|
||||
# GNSS system is self assesd as healthy |
||||
bool healthy |
||||
|
||||
# Status is actually a bitmask, due to encoding issues pretend it's just a field, and leave it up to the application do decode it) |
||||
uint23 STATUS_LOGGING = 1 # GNSS system is doing any onboard logging |
||||
uint23 STATUS_ARMABLE = 2 # GNSS system is in a reasonable state to allow the system to arm |
||||
uint23 status |
@ -1,3 +0,0 @@
@@ -1,3 +0,0 @@
|
||||
# length of data is set per the number of bytes for pkt in |
||||
# libraries/AP_GPS/RTCM3_Parser.h |
||||
uint8[<=300] data |
@ -1,8 +0,0 @@
@@ -1,8 +0,0 @@
|
||||
# timestamp on the gps message |
||||
uavcan.Timestamp timestamp |
||||
|
||||
bool reported_heading_acc_available |
||||
float32 reported_heading_deg |
||||
float32 reported_heading_acc_deg |
||||
float16 relative_distance_m |
||||
float16 relative_down_pos_m |
@ -1,7 +0,0 @@
@@ -1,7 +0,0 @@
|
||||
# |
||||
# support for Safety LED on UAVCAN |
||||
|
||||
uint8 STATUS_SAFETY_ON = 0 |
||||
uint8 STATUS_SAFETY_OFF = 255 |
||||
|
||||
uint8 status |
@ -1,11 +0,0 @@
@@ -1,11 +0,0 @@
|
||||
# |
||||
# support for buttons on UAVCAN |
||||
# while a button is being pressed this message should be sent at 10Hz |
||||
|
||||
uint8 BUTTON_SAFETY = 1 |
||||
|
||||
uint8 button |
||||
|
||||
# number of 0.1s units the button has been pressed for. If over 255 |
||||
# then send 255 |
||||
uint8 press_time |
@ -1,35 +0,0 @@
@@ -1,35 +0,0 @@
|
||||
uint8 VEHICLE_STATE_INITIALISING = 0 |
||||
uint8 VEHICLE_STATE_ARMED = 1 |
||||
uint8 VEHICLE_STATE_FLYING = 2 |
||||
uint8 VEHICLE_STATE_PREARM = 3 |
||||
uint8 VEHICLE_STATE_PREARM_GPS = 4 |
||||
uint8 VEHICLE_STATE_SAVE_TRIM = 5 |
||||
uint8 VEHICLE_STATE_ESC_CALIBRATION = 6 |
||||
uint8 VEHICLE_STATE_FAILSAFE_RADIO = 7 |
||||
uint8 VEHICLE_STATE_FAILSAFE_BATT = 8 |
||||
uint8 VEHICLE_STATE_FAILSAFE_GCS = 9 |
||||
uint8 VEHICLE_STATE_CHUTE_RELEASED = 10 |
||||
uint8 VEHICLE_STATE_EKF_BAD = 11 |
||||
uint8 VEHICLE_STATE_FW_UPDATE = 12 |
||||
uint8 VEHICLE_STATE_MAGCAL_RUN = 13 |
||||
uint8 VEHICLE_STATE_LEAK_DET = 14 |
||||
uint8 VEHICLE_STATE_GPS_FUSION = 15 |
||||
uint8 VEHICLE_STATE_GPS_GLITCH = 16 |
||||
uint8 VEHICLE_STATE_POS_ABS_AVAIL = 17 |
||||
uint8 VEHICLE_STATE_LOST = 18 |
||||
uint8 VEHICLE_STATE_THROW_READY = 19 |
||||
uint8 VEHICLE_STATE_POWERING_OFF = 20 |
||||
uint8 VEHICLE_STATE_VIDEO_RECORDING = 21 |
||||
|
||||
|
||||
uint8 VEHICLE_YAW_EARTH_CENTIDEGREES = 0 |
||||
|
||||
# set the type of aux data to be sent |
||||
uint8 aux_data_type |
||||
|
||||
# bytes containing packed auxiliary data |
||||
# placing it first so we don't do TAO |
||||
uint8[<=255] aux_data |
||||
|
||||
# Current Vehicle State Mask |
||||
uint64 vehicle_state |
@ -1,4 +0,0 @@
@@ -1,4 +0,0 @@
|
||||
float32 integration_interval # Integration Interval in seconds |
||||
float32[2] rate_gyro_integral # Integrated Gyro Data in radians |
||||
float32[2] flow_integral # Integrated LOS Data in radians |
||||
uint8 quality # Flow Data Quality Lowest(0)-Highest(255) Unitless |
Loading…
Reference in new issue