user_rid.h 6.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121
  1. #ifndef _USER_RID_H
  2. #define _USER_RID_H
  3. #include "stdint.h"
  4. #include "stdbool.h"
  5. #include "common.h"
  6. #include "canard.h"
  7. void send_msg_to_remoteid(void);
  8. enum Remoteid_type
  9. {
  10. LOCATION_TYPE = 1,
  11. SYS_OPERATOR_TYPE = 2,
  12. BASICID_TYPE = 3,
  13. SELFID_TYPE = 4,
  14. OPERATOR_TYPE = 5,
  15. ARMSTATUS_TYPE = 6,
  16. RID_TYPE_END,
  17. };
  18. bool remoteid_shouldAcceptTransfer(const CanardInstance *ins,
  19. uint64_t *out_data_type_signature,
  20. uint16_t data_type_id,
  21. CanardTransferType transfer_type,
  22. uint8_t source_node_id);
  23. int remoteid_OnRecieved(CanardInstance *canardIns,
  24. CanardRxTransfer *transfer);
  25. extern Connect_check remoteid_link;
  26. //remoteid
  27. #pragma pack(1)
  28. typedef struct{
  29. int32_t latitude; /*< [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).*/
  30. int32_t longitude; /*< [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).*/
  31. float altitude_barometric; /*< [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.*/
  32. float altitude_geodetic; /*< [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m.*/
  33. 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.*/
  34. 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.*/
  35. 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.*/
  36. 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.*/
  37. 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.*/
  38. uint8_t target_system; /*< System ID (0 for broadcast).*/
  39. uint8_t target_component; /*< Component ID (0 for broadcast).*/
  40. 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. */
  41. uint8_t status; /*< Indicates whether the unmanned aircraft is on the ground or in the air.*/
  42. uint8_t height_reference; /*< Indicates the reference point for the height field.*/
  43. uint8_t horizontal_accuracy; /*< The accuracy of the horizontal position.*/
  44. uint8_t vertical_accuracy; /*< The accuracy of the vertical position.*/
  45. uint8_t barometer_accuracy; /*< The accuracy of the barometric altitude.*/
  46. uint8_t speed_accuracy; /*< The accuracy of the horizontal and vertical speed.*/
  47. uint8_t timestamp_accuracy; /*< The accuracy of the timestamps.*/
  48. } _location_msg;
  49. #pragma pack()
  50. extern _location_msg locationId;
  51. #pragma pack(1)
  52. typedef struct{
  53. int32_t operator_latitude; /*< [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).*/
  54. int32_t operator_longitude; /*< [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).*/
  55. float area_ceiling; /*< [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.*/
  56. float area_floor; /*< [m] Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.*/
  57. float operator_altitude_geo; /*< [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.*/
  58. uint32_t timestamp; /*< [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.*/
  59. uint16_t area_count; /*< Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA.*/
  60. uint16_t area_radius; /*< [m] Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA.*/
  61. uint8_t target_system; /*< System ID (0 for broadcast).*/
  62. uint8_t target_component; /*< Component ID (0 for broadcast).*/
  63. 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. */
  64. uint8_t operator_location_type; /*< Specifies the operator location type.*/
  65. uint8_t classification_type; /*< Specifies the classification type of the UA.*/
  66. uint8_t category_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.*/
  67. uint8_t class_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.*/
  68. } _sys_operator_msg;
  69. #pragma pack()
  70. extern _sys_operator_msg systemId;
  71. #pragma pack(1)
  72. typedef struct {
  73. uint8_t target_system; /*< System ID (0 for broadcast).*/
  74. uint8_t target_component; /*< Component ID (0 for broadcast).*/
  75. 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. */
  76. uint8_t id_type; /*< Indicates the format for the uas_id field of this message.*/
  77. uint8_t ua_type; /*< Indicates the type of UA (Unmanned Aircraft).*/
  78. 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.*/
  79. } _basicId_msg;
  80. #pragma pack()
  81. extern _basicId_msg basicId;
  82. #pragma pack(1)
  83. typedef struct{
  84. uint8_t target_system; /*< System ID (0 for broadcast).*/
  85. uint8_t target_component; /*< Component ID (0 for broadcast).*/
  86. 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. */
  87. uint8_t description_type; /*< Indicates the type of the description field.*/
  88. char description[23]; /*< Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.*/
  89. } _selfId_msg;
  90. #pragma pack()
  91. extern _selfId_msg selfId;
  92. #pragma pack(1)
  93. typedef struct{
  94. uint8_t target_system; /*< System ID (0 for broadcast).*/
  95. uint8_t target_component; /*< Component ID (0 for broadcast).*/
  96. 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. */
  97. uint8_t operator_id_type; /*< Indicates the type of the operator_id field.*/
  98. 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.*/
  99. } _operatorId_msg;
  100. #pragma pack()
  101. extern _operatorId_msg operatorId;
  102. #pragma pack(1)
  103. typedef struct{
  104. uint8_t status;
  105. uint8_t len;
  106. uint8_t data[50];
  107. } _armStatusID_msg;
  108. #pragma pack()
  109. extern _armStatusID_msg StatusId;
  110. #endif