mirror of https://github.com/ArduPilot/ardupilot
AP_UAVCAN: added OpenDroneID support
This commit is contained in:
parent
02acf7b3a9
commit
d9ee361b3b
|
@ -53,6 +53,7 @@
|
|||
#include <AP_ADSB/AP_ADSB.h>
|
||||
#include "AP_UAVCAN_Server.h"
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_OpenDroneID/AP_OpenDroneID.h>
|
||||
|
||||
#define LED_DELAY_US 50000
|
||||
|
||||
|
@ -366,6 +367,9 @@ void AP_UAVCAN::loop(void)
|
|||
rtcm_stream_send();
|
||||
safety_state_send();
|
||||
AP::uavcan_server().verify_nodes(this);
|
||||
#if AP_OPENDRONEID_ENABLED
|
||||
AP::opendroneid().dronecan_send(this);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,33 @@
|
|||
#
|
||||
# DroneCAN version of MAVLink OPEN_DRONE_ID_BASIC_ID
|
||||
# see MAVLink XML for detailed description
|
||||
#
|
||||
uint8[<=20] id_or_mac
|
||||
|
||||
uint8 ODID_ID_TYPE_NONE = 0
|
||||
uint8 ODID_ID_TYPE_SERIAL_NUMBER = 1
|
||||
uint8 ODID_ID_TYPE_CAA_REGISTRATION_ID = 2
|
||||
uint8 ODID_ID_TYPE_UTM_ASSIGNED_UUID = 3
|
||||
uint8 ODID_ID_TYPE_SPECIFIC_SESSION_ID = 4
|
||||
|
||||
uint8 id_type
|
||||
|
||||
uint8 ODID_UA_TYPE_NONE = 0 # No UA (Unmanned Aircraft) type defined
|
||||
uint8 ODID_UA_TYPE_AEROPLANE = 1 # Aeroplane/Airplane. Fixed wing
|
||||
uint8 ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR = 2 # Helicopter or multirotor
|
||||
uint8 ODID_UA_TYPE_GYROPLANE = 3 # Gyroplane
|
||||
uint8 ODID_UA_TYPE_HYBRID_LIFT = 4 # VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically
|
||||
uint8 ODID_UA_TYPE_ORNITHOPTER = 5 # Ornithopter
|
||||
uint8 ODID_UA_TYPE_GLIDER = 6 # Glider
|
||||
uint8 ODID_UA_TYPE_KITE = 7 # Kite
|
||||
uint8 ODID_UA_TYPE_FREE_BALLOON = 8 # Free Balloon
|
||||
uint8 ODID_UA_TYPE_CAPTIVE_BALLOON = 9 # Captive Balloon
|
||||
uint8 ODID_UA_TYPE_AIRSHIP = 10 # Airship. E.g. a blimp
|
||||
uint8 ODID_UA_TYPE_FREE_FALL_PARACHUTE = 11 # Free Fall/Parachute (unpowered)
|
||||
uint8 ODID_UA_TYPE_ROCKET = 12 # Rocket
|
||||
uint8 ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT = 13 # Tethered powered aircraft
|
||||
uint8 ODID_UA_TYPE_GROUND_OBSTACLE = 14 # Ground Obstacle
|
||||
uint8 ODID_UA_TYPE_OTHER = 15 # Other type of aircraft not listed earlier
|
||||
|
||||
uint8 ua_type
|
||||
uint8[<=20] uas_id
|
|
@ -0,0 +1,78 @@
|
|||
#
|
||||
# DroneCAN version of MAVLink OPEN_DRONE_ID_LOCATION
|
||||
# see MAVLink XML for detailed description
|
||||
#
|
||||
uint8[<=20] id_or_mac
|
||||
|
||||
uint8 ODID_STATUS_UNDECLARED = 0 # The status of the (UA) Unmanned Aircraft is undefined
|
||||
uint8 ODID_STATUS_GROUND = 1 # The UA is on the ground
|
||||
uint8 ODID_STATUS_AIRBORNE = 2 # The UA is in the air
|
||||
uint8 ODID_STATUS_EMERGENCY = 3 # The UA is having an emergency
|
||||
uint8 status
|
||||
|
||||
uint16 direction # centi-deg, 0-35999
|
||||
uint16 speed_horizontal # cm/s, max 25425, if unknown use 25500
|
||||
int16 speed_vertical # positive up, max +/-6200, if unknown use 6300
|
||||
int32 latitude # degE7
|
||||
int32 longitude # degE7
|
||||
float32 altitude_barometric # meters, for unknown use -1000, ref is 29.92inHg or 1013.2mb
|
||||
float32 altitude_geodetic # meters, for unknown use -1000, WGS84
|
||||
|
||||
|
||||
uint8 ODID_HEIGHT_REF_OVER_TAKEOFF = 0 # The height field is relative to the take-off location
|
||||
uint8 ODID_HEIGHT_REF_OVER_GROUND = 1 # The height field is relative to ground
|
||||
uint8 height_reference
|
||||
|
||||
float32 height # meters, for unknown use -1000
|
||||
|
||||
uint8 ODID_HOR_ACC_UNKNOWN = 0 # The horizontal accuracy is unknown
|
||||
uint8 ODID_HOR_ACC_10NM = 1 # The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km
|
||||
uint8 ODID_HOR_ACC_4NM = 2 # The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km
|
||||
uint8 ODID_HOR_ACC_2NM = 3 # The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km
|
||||
uint8 ODID_HOR_ACC_1NM = 4 # The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km
|
||||
uint8 ODID_HOR_ACC_0_5NM = 5 # The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m
|
||||
uint8 ODID_HOR_ACC_0_3NM = 6 # The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m
|
||||
uint8 ODID_HOR_ACC_0_1NM = 7 # The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m
|
||||
uint8 ODID_HOR_ACC_0_05NM = 8 # The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m
|
||||
uint8 ODID_HOR_ACC_30_METER = 9 # The horizontal accuracy is smaller than 30 meter
|
||||
uint8 ODID_HOR_ACC_10_METER = 10 # The horizontal accuracy is smaller than 10 meter
|
||||
uint8 ODID_HOR_ACC_3_METER = 11 # The horizontal accuracy is smaller than 3 meter
|
||||
uint8 ODID_HOR_ACC_1_METER = 12 # The horizontal accuracy is smaller than 1 meter
|
||||
uint8 horizontal_accuracy
|
||||
|
||||
uint8 ODID_VER_ACC_UNKNOWN = 0 # The vertical accuracy is unknown
|
||||
uint8 ODID_VER_ACC_150_METER = 1 # The vertical accuracy is smaller than 150 meter
|
||||
uint8 ODID_VER_ACC_45_METER = 2 # The vertical accuracy is smaller than 45 meter
|
||||
uint8 ODID_VER_ACC_25_METER = 3 # The vertical accuracy is smaller than 25 meter
|
||||
uint8 ODID_VER_ACC_10_METER = 4 # The vertical accuracy is smaller than 10 meter
|
||||
uint8 ODID_VER_ACC_3_METER = 5 # The vertical accuracy is smaller than 3 meter
|
||||
uint8 ODID_VER_ACC_1_METER = 6 # The vertical accuracy is smaller than 1 meter
|
||||
uint8 vertical_accuracy
|
||||
uint8 barometer_accuracy
|
||||
|
||||
uint8 ODID_SPEED_ACC_UNKNOWN = 0 # The speed accuracy is unknown
|
||||
uint8 ODID_SPEED_ACC_10_METERS_PER_SECOND = 1 # The speed accuracy is smaller than 10 meters per second
|
||||
uint8 ODID_SPEED_ACC_3_METERS_PER_SECOND = 2 # The speed accuracy is smaller than 3 meters per second
|
||||
uint8 ODID_SPEED_ACC_1_METERS_PER_SECOND = 3 # The speed accuracy is smaller than 1 meters per second
|
||||
uint8 ODID_SPEED_ACC_0_3_METERS_PER_SECOND = 4 # The speed accuracy is smaller than 0.3 meters per second
|
||||
uint8 speed_accuracy
|
||||
|
||||
float32 timestamp # seconds after the full hour with reference to UTC time. Use 0xFFFF if unknown
|
||||
|
||||
uint8 ODID_TIME_ACC_0_1_SECOND = 1 # The timestamp accuracy is smaller than or equal to 0.1 second
|
||||
uint8 ODID_TIME_ACC_0_2_SECOND = 2 # The timestamp accuracy is smaller than or equal to 0.2 second
|
||||
uint8 ODID_TIME_ACC_0_3_SECOND = 3 # The timestamp accuracy is smaller than or equal to 0.3 second
|
||||
uint8 ODID_TIME_ACC_0_4_SECOND = 4 # The timestamp accuracy is smaller than or equal to 0.4 second
|
||||
uint8 ODID_TIME_ACC_0_5_SECOND = 5 # The timestamp accuracy is smaller than or equal to 0.5 second
|
||||
uint8 ODID_TIME_ACC_0_6_SECOND = 6 # The timestamp accuracy is smaller than or equal to 0.6 second
|
||||
uint8 ODID_TIME_ACC_0_7_SECOND = 7 # The timestamp accuracy is smaller than or equal to 0.7 second
|
||||
uint8 ODID_TIME_ACC_0_8_SECOND = 8 # The timestamp accuracy is smaller than or equal to 0.8 second
|
||||
uint8 ODID_TIME_ACC_0_9_SECOND = 9 # The timestamp accuracy is smaller than or equal to 0.9 second
|
||||
uint8 ODID_TIME_ACC_1_0_SECOND = 10 # The timestamp accuracy is smaller than or equal to 1.0 second
|
||||
uint8 ODID_TIME_ACC_1_1_SECOND = 11 # The timestamp accuracy is smaller than or equal to 1.1 second
|
||||
uint8 ODID_TIME_ACC_1_2_SECOND = 12 # The timestamp accuracy is smaller than or equal to 1.2 second
|
||||
uint8 ODID_TIME_ACC_1_3_SECOND = 13 # The timestamp accuracy is smaller than or equal to 1.3 second
|
||||
uint8 ODID_TIME_ACC_1_4_SECOND = 14 # The timestamp accuracy is smaller than or equal to 1.4 second
|
||||
uint8 ODID_TIME_ACC_1_5_SECOND = 15 # The timestamp accuracy is smaller than or equal to 1.5 second
|
||||
uint8 timestamp_accuracy
|
||||
|
|
@ -0,0 +1,10 @@
|
|||
#
|
||||
# DroneCAN version of MAVLink OPEN_DRONE_ID_SELF_ID
|
||||
# see MAVLink XML for detailed description
|
||||
#
|
||||
uint8[<=20] id_or_mac
|
||||
|
||||
uint8 ODID_DESC_TYPE_TEXT = 0 # Free-form text description of the purpose of the flight
|
||||
uint8 description_type
|
||||
uint8[<=23] description
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
#
|
||||
# DroneCAN version of MAVLink OPEN_DRONE_ID_SYSTEM
|
||||
# see MAVLink XML for detailed description
|
||||
#
|
||||
uint8[<=20] id_or_mac
|
||||
|
||||
uint8 ODID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0 # The location of the operator is the same as the take-off location
|
||||
uint8 ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1 # The location of the operator is based on live GNSS data
|
||||
uint8 ODID_OPERATOR_LOCATION_TYPE_FIXED = 2 # The location of the operator is a fixed location
|
||||
uint8 operator_location_type
|
||||
|
||||
uint8 ODID_CLASSIFICATION_TYPE_EU = 0
|
||||
uint8 classification_type
|
||||
|
||||
int32 operator_latitude # degE7
|
||||
int32 operator_longitude # degE7
|
||||
uint16 area_count # default 1
|
||||
uint16 area_radius # meters
|
||||
float32 area_ceiling # meters, use -1000 if unknown, WGS84
|
||||
float32 area_floor # meters, use -1000 if unknown, WGS84
|
||||
|
||||
uint8 ODID_CATEGORY_EU_UNDECLARED = 0 # The category for the UA, according to the EU specification, is undeclared
|
||||
uint8 ODID_CATEGORY_EU_OPEN = 1 # The category for the UA, according to the EU specification, is the Open category
|
||||
uint8 ODID_CATEGORY_EU_SPECIFIC = 2 # The category for the UA, according to the EU specification, is the Specific category
|
||||
uint8 ODID_CATEGORY_EU_CERTIFIED = 3 # The category for the UA, according to the EU specification, is the Certified category
|
||||
uint8 category_eu
|
||||
|
||||
uint8 ODID_CLASS_EU_UNDECLARED = 0 # The class for the UA, according to the EU specification, is undeclared
|
||||
uint8 ODID_CLASS_EU_CLASS_0 = 1 # The class for the UA, according to the EU specification, is Class 0
|
||||
uint8 ODID_CLASS_EU_CLASS_1 = 2 # The class for the UA, according to the EU specification, is Class 1
|
||||
uint8 ODID_CLASS_EU_CLASS_2 = 3 # The class for the UA, according to the EU specification, is Class 2
|
||||
uint8 ODID_CLASS_EU_CLASS_3 = 4 # The class for the UA, according to the EU specification, is Class 3
|
||||
uint8 ODID_CLASS_EU_CLASS_4 = 5 # The class for the UA, according to the EU specification, is Class 4
|
||||
uint8 ODID_CLASS_EU_CLASS_5 = 6 # The class for the UA, according to the EU specification, is Class 5
|
||||
uint8 ODID_CLASS_EU_CLASS_6 = 7 # The class for the UA, according to the EU specification, is Class 6
|
||||
uint8 class_eu
|
||||
|
||||
float32 operator_altitude_geo # meters, use -1000 if unknown, WGS84
|
||||
uint32 timestamp # Unix seconds since 00:00:00 01/01/2019
|
||||
|
|
@ -0,0 +1,11 @@
|
|||
#
|
||||
# DroneCAN version of MAVLink OPEN_DRONE_ID_OPERATOR_ID
|
||||
# see MAVLink XML for detailed description
|
||||
#
|
||||
uint8[<=20] id_or_mac
|
||||
|
||||
uint8 ODID_OPERATOR_ID_TYPE_CAA = 0 # CAA (Civil Aviation Authority) registered operator ID
|
||||
uint8 operator_id_type
|
||||
|
||||
uint8[<=20] operator_id
|
||||
|
|
@ -0,0 +1,10 @@
|
|||
#
|
||||
# DroneCAN version of MAVLink OPEN_DRONE_ID_ARM_STATUS
|
||||
# see MAVLink XML for detailed description
|
||||
#
|
||||
uint8 ODID_ARM_STATUS_GOOD_TO_ARM = 0
|
||||
uint8 ODID_ARM_STATUS_FAIL_GENERIC = 1
|
||||
uint8 status
|
||||
|
||||
uint8[<=50] error
|
||||
|
Loading…
Reference in New Issue