RemoteIDModule.ino 8.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217
  1. /*
  2. implement OpenDroneID MAVLink and DroneCAN support
  3. */
  4. /*
  5. released under GNU GPL v3 or later
  6. */
  7. #include <Arduino.h>
  8. #include "version.h"
  9. #include <math.h>
  10. #include <time.h>
  11. #include <sys/time.h>
  12. #include <opendroneid.h>
  13. #include "mavlink.h"
  14. #include "DroneCAN.h"
  15. #include "WiFi_TX.h"
  16. #include "BLE_TX.h"
  17. static DroneCAN dronecan;
  18. static MAVLinkSerial mavlink{Serial1, MAVLINK_COMM_0};
  19. static WiFi_NAN wifi;
  20. static BLE_TX ble;
  21. #define OUTPUT_RATE_HZ 5
  22. /*
  23. assume ESP32-s3 for now, using pins 17 and 18 for uart
  24. */
  25. #define RX_PIN 17
  26. #define TX_PIN 18
  27. #define DEBUG_BAUDRATE 57600
  28. #define MAVLINK_BAUDRATE 57600
  29. // OpenDroneID output data structure
  30. static ODID_UAS_Data UAS_data;
  31. /*
  32. setup serial ports
  33. */
  34. void setup()
  35. {
  36. // Serial for debug printf
  37. Serial.begin(DEBUG_BAUDRATE);
  38. Serial.printf("ArduRemoteID version %u.%u %08x\n",
  39. FW_VERSION_MAJOR, FW_VERSION_MINOR, GIT_VERSION);
  40. // Serial1 for MAVLink
  41. Serial1.begin(MAVLINK_BAUDRATE, SERIAL_8N1, RX_PIN, TX_PIN);
  42. mavlink.init();
  43. dronecan.init();
  44. wifi.init();
  45. ble.init();
  46. }
  47. #define MIN(x,y) ((x)<(y)?(x):(y))
  48. #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, MIN(sizeof(to), sizeof(from)))
  49. static void set_data_mavlink(void)
  50. {
  51. const auto &operator_id = mavlink.get_operator_id();
  52. const auto &basic_id = mavlink.get_basic_id();
  53. const auto &system = mavlink.get_system();
  54. const auto &self_id = mavlink.get_self_id();
  55. const auto &location = mavlink.get_location();
  56. // BasicID
  57. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  58. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  59. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  60. UAS_data.BasicIDValid[0] = 1;
  61. // OperatorID
  62. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  63. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  64. UAS_data.OperatorIDValid = 1;
  65. // SelfID
  66. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  67. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  68. UAS_data.SelfIDValid = 1;
  69. // System
  70. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  71. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  72. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  73. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  74. UAS_data.System.AreaCount = system.area_count;
  75. UAS_data.System.AreaRadius = system.area_radius;
  76. UAS_data.System.AreaCeiling = system.area_ceiling;
  77. UAS_data.System.AreaFloor = system.area_floor;
  78. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  79. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  80. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  81. UAS_data.System.Timestamp = system.timestamp;
  82. UAS_data.SystemValid = 1;
  83. // Location
  84. UAS_data.Location.Status = (ODID_status_t)location.status;
  85. UAS_data.Location.Direction = location.direction*0.01;
  86. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  87. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  88. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  89. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  90. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  91. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  92. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  93. UAS_data.Location.Height = location.height;
  94. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  95. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  96. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  97. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  98. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  99. UAS_data.Location.TimeStamp = location.timestamp;
  100. UAS_data.LocationValid = 1;
  101. }
  102. #undef ODID_COPY_STR
  103. #define ODID_COPY_STR(to, from) memcpy(to, from.data, MIN(from.len, sizeof(to)))
  104. static void set_data_dronecan(void)
  105. {
  106. const auto &operator_id = dronecan.get_operator_id();
  107. const auto &basic_id = dronecan.get_basic_id();
  108. const auto &system = dronecan.get_system();
  109. const auto &self_id = dronecan.get_self_id();
  110. const auto &location = dronecan.get_location();
  111. // BasicID
  112. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  113. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  114. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  115. UAS_data.BasicIDValid[0] = 1;
  116. // OperatorID
  117. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  118. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  119. UAS_data.OperatorIDValid = 1;
  120. // SelfID
  121. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  122. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  123. UAS_data.SelfIDValid = 1;
  124. // System
  125. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  126. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  127. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  128. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  129. UAS_data.System.AreaCount = system.area_count;
  130. UAS_data.System.AreaRadius = system.area_radius;
  131. UAS_data.System.AreaCeiling = system.area_ceiling;
  132. UAS_data.System.AreaFloor = system.area_floor;
  133. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  134. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  135. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  136. UAS_data.System.Timestamp = system.timestamp;
  137. UAS_data.SystemValid = 1;
  138. // Location
  139. UAS_data.Location.Status = (ODID_status_t)location.status;
  140. UAS_data.Location.Direction = location.direction*0.01;
  141. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  142. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  143. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  144. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  145. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  146. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  147. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  148. UAS_data.Location.Height = location.height;
  149. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  150. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  151. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  152. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  153. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  154. UAS_data.Location.TimeStamp = location.timestamp;
  155. UAS_data.LocationValid = 1;
  156. }
  157. static uint8_t beacon_payload[256];
  158. void loop()
  159. {
  160. static uint32_t last_update;
  161. mavlink.update();
  162. dronecan.update();
  163. const uint32_t now_ms = millis();
  164. if (now_ms - last_update < 1000/OUTPUT_RATE_HZ) {
  165. // not ready for a new frame yet
  166. return;
  167. }
  168. const bool mavlink_ok = mavlink.location_valid() && mavlink.system_valid();
  169. const bool dronecan_ok = dronecan.location_valid() && dronecan.system_valid();
  170. if (!mavlink_ok && !dronecan_ok) {
  171. return;
  172. }
  173. if (mavlink_ok) {
  174. set_data_mavlink();
  175. }
  176. if (dronecan_ok) {
  177. set_data_dronecan();
  178. }
  179. last_update = now_ms;
  180. const auto length = odid_message_build_pack(&UAS_data,beacon_payload,255);
  181. wifi.transmit(UAS_data);
  182. ble.transmit(UAS_data);
  183. }