RemoteIDModule.ino 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267
  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 mavlink1{Serial1, MAVLINK_COMM_0};
  19. static MAVLinkSerial mavlink2{Serial, MAVLINK_COMM_1};
  20. static WiFi_NAN wifi;
  21. static BLE_TX ble;
  22. #define OUTPUT_RATE_HZ 5
  23. /*
  24. assume ESP32-s3 for now, using pins 17 and 18 for uart
  25. */
  26. #define RX_PIN 17
  27. #define TX_PIN 18
  28. #define DEBUG_BAUDRATE 57600
  29. #define MAVLINK_BAUDRATE 57600
  30. // OpenDroneID output data structure
  31. static ODID_UAS_Data UAS_data;
  32. /*
  33. setup serial ports
  34. */
  35. void setup()
  36. {
  37. // Serial for debug printf
  38. Serial.begin(DEBUG_BAUDRATE);
  39. Serial.printf("ArduRemoteID version %u.%u %08x\n",
  40. FW_VERSION_MAJOR, FW_VERSION_MINOR, GIT_VERSION);
  41. // Serial1 for MAVLink
  42. Serial1.begin(MAVLINK_BAUDRATE, SERIAL_8N1, RX_PIN, TX_PIN);
  43. mavlink1.init();
  44. mavlink2.init();
  45. dronecan.init();
  46. wifi.init();
  47. ble.init();
  48. }
  49. #define MIN(x,y) ((x)<(y)?(x):(y))
  50. #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, MIN(sizeof(to), sizeof(from)))
  51. /*
  52. check parsing of UAS_data, this checks ranges of values to ensure we
  53. will produce a valid pack
  54. */
  55. static const char *check_parse(void)
  56. {
  57. {
  58. ODID_Location_encoded encoded {};
  59. if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
  60. return "bad LOCATION data";
  61. }
  62. }
  63. {
  64. ODID_System_encoded encoded {};
  65. if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
  66. return "bad SYSTEM data";
  67. }
  68. }
  69. {
  70. ODID_BasicID_encoded encoded {};
  71. if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  72. return "bad BASIC_ID data";
  73. }
  74. }
  75. {
  76. ODID_SelfID_encoded encoded {};
  77. if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  78. return "bad SELF_ID data";
  79. }
  80. }
  81. {
  82. ODID_OperatorID_encoded encoded {};
  83. if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  84. return "bad OPERATOR_ID data";
  85. }
  86. }
  87. return nullptr;
  88. }
  89. static void set_data_mavlink(MAVLinkSerial &m)
  90. {
  91. const auto &operator_id = m.get_operator_id();
  92. const auto &basic_id = m.get_basic_id();
  93. const auto &system = m.get_system();
  94. const auto &self_id = m.get_self_id();
  95. const auto &location = m.get_location();
  96. // BasicID
  97. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  98. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  99. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  100. UAS_data.BasicIDValid[0] = 1;
  101. // OperatorID
  102. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  103. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  104. UAS_data.OperatorIDValid = 1;
  105. // SelfID
  106. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  107. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  108. UAS_data.SelfIDValid = 1;
  109. // System
  110. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  111. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  112. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  113. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  114. UAS_data.System.AreaCount = system.area_count;
  115. UAS_data.System.AreaRadius = system.area_radius;
  116. UAS_data.System.AreaCeiling = system.area_ceiling;
  117. UAS_data.System.AreaFloor = system.area_floor;
  118. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  119. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  120. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  121. UAS_data.System.Timestamp = system.timestamp;
  122. UAS_data.SystemValid = 1;
  123. // Location
  124. UAS_data.Location.Status = (ODID_status_t)location.status;
  125. UAS_data.Location.Direction = location.direction*0.01;
  126. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  127. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  128. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  129. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  130. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  131. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  132. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  133. UAS_data.Location.Height = location.height;
  134. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  135. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  136. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  137. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  138. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  139. UAS_data.Location.TimeStamp = location.timestamp;
  140. UAS_data.LocationValid = 1;
  141. m.set_parse_fail(check_parse());
  142. }
  143. #undef ODID_COPY_STR
  144. #define ODID_COPY_STR(to, from) memcpy(to, from.data, MIN(from.len, sizeof(to)))
  145. static void set_data_dronecan(void)
  146. {
  147. const auto &operator_id = dronecan.get_operator_id();
  148. const auto &basic_id = dronecan.get_basic_id();
  149. const auto &system = dronecan.get_system();
  150. const auto &self_id = dronecan.get_self_id();
  151. const auto &location = dronecan.get_location();
  152. // BasicID
  153. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  154. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  155. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  156. UAS_data.BasicIDValid[0] = 1;
  157. // OperatorID
  158. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  159. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  160. UAS_data.OperatorIDValid = 1;
  161. // SelfID
  162. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  163. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  164. UAS_data.SelfIDValid = 1;
  165. // System
  166. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  167. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  168. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  169. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  170. UAS_data.System.AreaCount = system.area_count;
  171. UAS_data.System.AreaRadius = system.area_radius;
  172. UAS_data.System.AreaCeiling = system.area_ceiling;
  173. UAS_data.System.AreaFloor = system.area_floor;
  174. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  175. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  176. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  177. UAS_data.System.Timestamp = system.timestamp;
  178. UAS_data.SystemValid = 1;
  179. // Location
  180. UAS_data.Location.Status = (ODID_status_t)location.status;
  181. UAS_data.Location.Direction = location.direction*0.01;
  182. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  183. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  184. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  185. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  186. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  187. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  188. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  189. UAS_data.Location.Height = location.height;
  190. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  191. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  192. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  193. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  194. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  195. UAS_data.Location.TimeStamp = location.timestamp;
  196. UAS_data.LocationValid = 1;
  197. dronecan.set_parse_fail(check_parse());
  198. }
  199. static uint8_t beacon_payload[256];
  200. void loop()
  201. {
  202. static uint32_t last_update;
  203. mavlink1.update();
  204. mavlink2.update();
  205. dronecan.update();
  206. const uint32_t now_ms = millis();
  207. if (now_ms - last_update < 1000/OUTPUT_RATE_HZ) {
  208. // not ready for a new frame yet
  209. return;
  210. }
  211. const bool mavlink1_ok = mavlink1.location_valid() && mavlink1.system_valid();
  212. const bool mavlink2_ok = mavlink2.location_valid() && mavlink2.system_valid();
  213. const bool dronecan_ok = dronecan.location_valid() && dronecan.system_valid();
  214. if (!mavlink1_ok && !mavlink2_ok && !dronecan_ok) {
  215. return;
  216. }
  217. if (mavlink1_ok) {
  218. set_data_mavlink(mavlink1);
  219. }
  220. if (mavlink2_ok) {
  221. set_data_mavlink(mavlink2);
  222. }
  223. if (dronecan_ok) {
  224. set_data_dronecan();
  225. }
  226. last_update = now_ms;
  227. const auto length = odid_message_build_pack(&UAS_data,beacon_payload,255);
  228. wifi.transmit(UAS_data);
  229. ble.transmit(UAS_data);
  230. }