#ifndef _USER_RID_H #define _USER_RID_H #include "stdint.h" #include "stdbool.h" #include "common.h" #include "canard.h" void send_msg_to_remoteid(void); enum Remoteid_type { LOCATION_TYPE = 1, SYS_OPERATOR_TYPE = 2, BASICID_TYPE = 3, SELFID_TYPE = 4, OPERATOR_TYPE = 5, ARMSTATUS_TYPE = 6, RID_TYPE_END, }; bool remoteid_shouldAcceptTransfer(const CanardInstance *ins, uint64_t *out_data_type_signature, uint16_t data_type_id, CanardTransferType transfer_type, uint8_t source_node_id); int remoteid_OnRecieved(CanardInstance *canardIns, CanardRxTransfer *transfer); extern Connect_check remoteid_link; //remoteid #pragma pack(1) typedef struct{ int32_t latitude; /*< [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).*/ int32_t longitude; /*< [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).*/ float altitude_barometric; /*< [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.*/ float altitude_geodetic; /*< [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m.*/ float height; /*< [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.*/ float timestamp; /*< [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF.*/ uint16_t direction; /*< [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.*/ uint16_t speed_horizontal; /*< [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.*/ int16_t speed_vertical; /*< [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.*/ uint8_t target_system; /*< System ID (0 for broadcast).*/ uint8_t target_component; /*< Component ID (0 for broadcast).*/ uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ uint8_t status; /*< Indicates whether the unmanned aircraft is on the ground or in the air.*/ uint8_t height_reference; /*< Indicates the reference point for the height field.*/ uint8_t horizontal_accuracy; /*< The accuracy of the horizontal position.*/ uint8_t vertical_accuracy; /*< The accuracy of the vertical position.*/ uint8_t barometer_accuracy; /*< The accuracy of the barometric altitude.*/ uint8_t speed_accuracy; /*< The accuracy of the horizontal and vertical speed.*/ uint8_t timestamp_accuracy; /*< The accuracy of the timestamps.*/ } _location_msg; #pragma pack() extern _location_msg locationId; #pragma pack(1) typedef struct{ int32_t operator_latitude; /*< [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).*/ int32_t operator_longitude; /*< [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).*/ float area_ceiling; /*< [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.*/ float area_floor; /*< [m] Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.*/ float operator_altitude_geo; /*< [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.*/ uint32_t timestamp; /*< [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.*/ uint16_t area_count; /*< Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA.*/ uint16_t area_radius; /*< [m] Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA.*/ uint8_t target_system; /*< System ID (0 for broadcast).*/ uint8_t target_component; /*< Component ID (0 for broadcast).*/ uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ uint8_t operator_location_type; /*< Specifies the operator location type.*/ uint8_t classification_type; /*< Specifies the classification type of the UA.*/ uint8_t category_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.*/ uint8_t class_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.*/ } _sys_operator_msg; #pragma pack() extern _sys_operator_msg systemId; #pragma pack(1) typedef struct { uint8_t target_system; /*< System ID (0 for broadcast).*/ uint8_t target_component; /*< Component ID (0 for broadcast).*/ uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ uint8_t id_type; /*< Indicates the format for the uas_id field of this message.*/ uint8_t ua_type; /*< Indicates the type of UA (Unmanned Aircraft).*/ uint8_t uas_id[20]; /*< UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.*/ } _basicId_msg; #pragma pack() extern _basicId_msg basicId; #pragma pack(1) typedef struct{ uint8_t target_system; /*< System ID (0 for broadcast).*/ uint8_t target_component; /*< Component ID (0 for broadcast).*/ uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ uint8_t description_type; /*< Indicates the type of the description field.*/ char description[23]; /*< Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.*/ } _selfId_msg; #pragma pack() extern _selfId_msg selfId; #pragma pack(1) typedef struct{ uint8_t target_system; /*< System ID (0 for broadcast).*/ uint8_t target_component; /*< Component ID (0 for broadcast).*/ uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ uint8_t operator_id_type; /*< Indicates the type of the operator_id field.*/ char operator_id[20]; /*< Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.*/ } _operatorId_msg; #pragma pack() extern _operatorId_msg operatorId; #pragma pack(1) typedef struct{ uint8_t status; uint8_t len; uint8_t data[50]; } _armStatusID_msg; #pragma pack() extern _armStatusID_msg StatusId; #endif