RemoteIDModule.ino 11 KB

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