RemoteIDModule.ino 12 KB

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