RemoteIDModule.ino 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456
  1. /*
  2. implement OpenDroneID MAVLink and DroneCAN support
  3. */
  4. /*
  5. released under GNU GPL v2 or later
  6. */
  7. #include "options.h"
  8. #include <Arduino.h>
  9. #include "version.h"
  10. #include <math.h>
  11. #include <time.h>
  12. #include <sys/time.h>
  13. #include <opendroneid.h>
  14. #include "mavlink.h"
  15. #include "DroneCAN.h"
  16. #include "WiFi_TX.h"
  17. #include "BLE_TX.h"
  18. #include <esp_wifi.h>
  19. #include <WiFi.h>
  20. #include "parameters.h"
  21. #include "webinterface.h"
  22. #include "check_firmware.h"
  23. #include <esp_ota_ops.h>
  24. #include "efuse.h"
  25. #include "led.h"
  26. #if AP_DRONECAN_ENABLED
  27. static DroneCAN dronecan;
  28. #endif
  29. #if AP_MAVLINK_ENABLED
  30. static MAVLinkSerial mavlink1{Serial1, MAVLINK_COMM_0};
  31. static MAVLinkSerial mavlink2{Serial, MAVLINK_COMM_1};
  32. #endif
  33. static WiFi_TX wifi;
  34. static BLE_TX ble;
  35. #define DEBUG_BAUDRATE 57600
  36. // OpenDroneID output data structure
  37. ODID_UAS_Data UAS_data;
  38. String status_reason;
  39. static uint32_t last_location_ms;
  40. static WebInterface webif;
  41. #include "soc/soc.h"
  42. #include "soc/rtc_cntl_reg.h"
  43. static bool arm_check_ok = false; // goes true for LED arm check status
  44. static bool pfst_check_ok = false;
  45. /*
  46. setup serial ports
  47. */
  48. void setup()
  49. {
  50. // disable brownout checking
  51. WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
  52. g.init();
  53. led.set_state(Led::LedState::INIT);
  54. led.update();
  55. if (g.webserver_enable) {
  56. // need WiFi for web server
  57. wifi.init();
  58. }
  59. // Serial for debug printf
  60. Serial.begin(g.baudrate);
  61. // Serial1 for MAVLink
  62. Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
  63. // set all fields to invalid/initial values
  64. odid_initUasData(&UAS_data);
  65. #if AP_MAVLINK_ENABLED
  66. mavlink1.init();
  67. mavlink2.init();
  68. #endif
  69. #if AP_DRONECAN_ENABLED
  70. dronecan.init();
  71. #endif
  72. set_efuses();
  73. CheckFirmware::check_OTA_running();
  74. #if defined(PIN_CAN_EN)
  75. // optional CAN enable pin
  76. pinMode(PIN_CAN_EN, OUTPUT);
  77. digitalWrite(PIN_CAN_EN, HIGH);
  78. #endif
  79. #if defined(PIN_CAN_nSILENT)
  80. // disable silent pin
  81. pinMode(PIN_CAN_nSILENT, OUTPUT);
  82. digitalWrite(PIN_CAN_nSILENT, HIGH);
  83. #endif
  84. #if defined(PIN_CAN_TERM)
  85. #if !defined(CAN_TERM_EN)
  86. #define CAN_TERM_EN HIGH
  87. #endif
  88. // optional CAN termination control
  89. pinMode(PIN_CAN_TERM, OUTPUT);
  90. if (g.can_term == 1) {
  91. digitalWrite(PIN_CAN_TERM, CAN_TERM_EN);
  92. } else {
  93. digitalWrite(PIN_CAN_TERM, !CAN_TERM_EN);
  94. }
  95. #endif
  96. #if defined(BUZZER_PIN)
  97. //set BuZZER OUTPUT ACTIVE, just to show it works
  98. pinMode(GPIO_NUM_39, OUTPUT);
  99. digitalWrite(GPIO_NUM_39, HIGH);
  100. #endif
  101. pfst_check_ok = true; // note - this will need to be expanded to better capture PFST test status
  102. // initially set LED for fail
  103. led.set_state(Led::LedState::ARM_FAIL);
  104. esp_log_level_set("*", ESP_LOG_DEBUG);
  105. esp_ota_mark_app_valid_cancel_rollback();
  106. }
  107. #define IMIN(x,y) ((x)<(y)?(x):(y))
  108. #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
  109. /*
  110. check parsing of UAS_data, this checks ranges of values to ensure we
  111. will produce a valid pack
  112. returns nullptr on no error, or a string error
  113. */
  114. static const char *check_parse(void)
  115. {
  116. String ret = "";
  117. {
  118. ODID_Location_encoded encoded {};
  119. if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
  120. ret += "LOC ";
  121. }
  122. }
  123. {
  124. ODID_System_encoded encoded {};
  125. if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
  126. ret += "SYS ";
  127. }
  128. }
  129. {
  130. ODID_BasicID_encoded encoded {};
  131. if (UAS_data.BasicIDValid[0] == 1) {
  132. if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  133. ret += "ID_1 ";
  134. }
  135. }
  136. memset(&encoded, 0, sizeof(encoded));
  137. if (UAS_data.BasicIDValid[1] == 1) {
  138. if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[1]) != ODID_SUCCESS) {
  139. ret += "ID_2 ";
  140. }
  141. }
  142. }
  143. {
  144. ODID_SelfID_encoded encoded {};
  145. if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  146. ret += "SELF_ID ";
  147. }
  148. }
  149. {
  150. ODID_OperatorID_encoded encoded {};
  151. if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  152. ret += "OP_ID ";
  153. }
  154. }
  155. if (ret.length() > 0) {
  156. // if all errors would occur in this function, it will fit in
  157. // 50 chars that is also the max for the arm status message
  158. static char return_string[50];
  159. memset(return_string, 0, sizeof(return_string));
  160. snprintf(return_string, sizeof(return_string)-1, "bad %s data", ret.c_str());
  161. return return_string;
  162. }
  163. return nullptr;
  164. }
  165. /*
  166. fill in UAS_data from MAVLink packets
  167. */
  168. static void set_data(Transport &t)
  169. {
  170. const auto &operator_id = t.get_operator_id();
  171. const auto &basic_id = t.get_basic_id();
  172. const auto &system = t.get_system();
  173. const auto &self_id = t.get_self_id();
  174. const auto &location = t.get_location();
  175. odid_initUasData(&UAS_data);
  176. /*
  177. if we don't have BasicID info from parameters and we have it
  178. from the DroneCAN or MAVLink transport then copy it to the
  179. parameters to persist it. This makes it possible to set the
  180. UAS_ID string via a MAVLink BASIC_ID message and also offers a
  181. migration path from the old approach of GCS setting these values
  182. to having them as parameters
  183. BasicID 2 can be set in parameters, or provided via mavlink We
  184. don't persist the BasicID2 if provided via mavlink to allow
  185. users to change BasicID2 on different days
  186. */
  187. if (!g.have_basic_id_info() && !(g.options & OPTIONS_DONT_SAVE_BASIC_ID_TO_PARAMETERS)) {
  188. if (basic_id.ua_type != 0 &&
  189. basic_id.id_type != 0 &&
  190. strnlen((const char *)basic_id.uas_id, 20) > 0) {
  191. g.set_by_name_uint8("UAS_TYPE", basic_id.ua_type);
  192. g.set_by_name_uint8("UAS_ID_TYPE", basic_id.id_type);
  193. char uas_id[21] {};
  194. ODID_COPY_STR(uas_id, basic_id.uas_id);
  195. g.set_by_name_string("UAS_ID", uas_id);
  196. }
  197. }
  198. // BasicID
  199. if (g.have_basic_id_info() && !(g.options & OPTIONS_DONT_SAVE_BASIC_ID_TO_PARAMETERS)) {
  200. // from parameters
  201. UAS_data.BasicID[0].UAType = (ODID_uatype_t)g.ua_type;
  202. UAS_data.BasicID[0].IDType = (ODID_idtype_t)g.id_type;
  203. ODID_COPY_STR(UAS_data.BasicID[0].UASID, g.uas_id);
  204. UAS_data.BasicIDValid[0] = 1;
  205. // BasicID 2
  206. if (g.have_basic_id_2_info()) {
  207. // from parameters
  208. UAS_data.BasicID[1].UAType = (ODID_uatype_t)g.ua_type_2;
  209. UAS_data.BasicID[1].IDType = (ODID_idtype_t)g.id_type_2;
  210. ODID_COPY_STR(UAS_data.BasicID[1].UASID, g.uas_id_2);
  211. UAS_data.BasicIDValid[1] = 1;
  212. } else if (strcmp((const char*)g.uas_id, (const char*)basic_id.uas_id) != 0) {
  213. /*
  214. no BasicID 2 in the parameters, if one is provided on MAVLink
  215. and it is a different uas_id from the basicID1 then use it as BasicID2
  216. */
  217. if (basic_id.ua_type != 0 &&
  218. basic_id.id_type != 0 &&
  219. strnlen((const char *)basic_id.uas_id, 20) > 0) {
  220. UAS_data.BasicID[1].UAType = (ODID_uatype_t)basic_id.ua_type;
  221. UAS_data.BasicID[1].IDType = (ODID_idtype_t)basic_id.id_type;
  222. ODID_COPY_STR(UAS_data.BasicID[1].UASID, basic_id.uas_id);
  223. UAS_data.BasicIDValid[1] = 1;
  224. }
  225. }
  226. }
  227. if (g.options & OPTIONS_DONT_SAVE_BASIC_ID_TO_PARAMETERS) {
  228. if (basic_id.ua_type != 0 &&
  229. basic_id.id_type != 0 &&
  230. strnlen((const char *)basic_id.uas_id, 20) > 0) {
  231. if (strcmp((const char*)UAS_data.BasicID[0].UASID, (const char*)basic_id.uas_id) != 0 && strnlen((const char *)basic_id.uas_id, 20) > 0) {
  232. UAS_data.BasicID[1].UAType = (ODID_uatype_t)basic_id.ua_type;
  233. UAS_data.BasicID[1].IDType = (ODID_idtype_t)basic_id.id_type;
  234. ODID_COPY_STR(UAS_data.BasicID[1].UASID, basic_id.uas_id);
  235. UAS_data.BasicIDValid[1] = 1;
  236. } else {
  237. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  238. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  239. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  240. UAS_data.BasicIDValid[0] = 1;
  241. }
  242. }
  243. }
  244. // OperatorID
  245. if (strlen(operator_id.operator_id) > 0) {
  246. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  247. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  248. UAS_data.OperatorIDValid = 1;
  249. }
  250. // SelfID
  251. if (strlen(self_id.description) > 0) {
  252. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  253. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  254. UAS_data.SelfIDValid = 1;
  255. }
  256. // System
  257. if (system.timestamp != 0) {
  258. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  259. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  260. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  261. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  262. UAS_data.System.AreaCount = system.area_count;
  263. UAS_data.System.AreaRadius = system.area_radius;
  264. UAS_data.System.AreaCeiling = system.area_ceiling;
  265. UAS_data.System.AreaFloor = system.area_floor;
  266. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  267. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  268. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  269. UAS_data.System.Timestamp = system.timestamp;
  270. UAS_data.SystemValid = 1;
  271. }
  272. // Location
  273. if (location.timestamp != 0) {
  274. UAS_data.Location.Status = (ODID_status_t)location.status;
  275. UAS_data.Location.Direction = location.direction*0.01;
  276. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  277. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  278. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  279. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  280. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  281. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  282. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  283. UAS_data.Location.Height = location.height;
  284. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  285. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  286. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  287. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  288. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  289. UAS_data.Location.TimeStamp = location.timestamp;
  290. UAS_data.LocationValid = 1;
  291. }
  292. const char *reason = check_parse();
  293. t.arm_status_check(reason);
  294. t.set_parse_fail(reason);
  295. arm_check_ok = (reason==nullptr);
  296. if (g.options & OPTIONS_FORCE_ARM_OK) {
  297. arm_check_ok = true;
  298. }
  299. led.set_state(pfst_check_ok && arm_check_ok? Led::LedState::ARM_OK : Led::LedState::ARM_FAIL);
  300. uint32_t now_ms = millis();
  301. uint32_t location_age_ms = now_ms - t.get_last_location_ms();
  302. uint32_t last_location_age_ms = now_ms - last_location_ms;
  303. if (location_age_ms < last_location_age_ms) {
  304. last_location_ms = t.get_last_location_ms();
  305. }
  306. }
  307. static uint8_t loop_counter = 0;
  308. void loop()
  309. {
  310. #if AP_MAVLINK_ENABLED
  311. mavlink1.update();
  312. mavlink2.update();
  313. #endif
  314. #if AP_DRONECAN_ENABLED
  315. dronecan.update();
  316. #endif
  317. const uint32_t now_ms = millis();
  318. // the transports have common static data, so we can just use the
  319. // first for status
  320. #if AP_MAVLINK_ENABLED
  321. auto &transport = mavlink1;
  322. #elif AP_DRONECAN_ENABLED
  323. auto &transport = dronecan;
  324. #else
  325. #error "Must enable DroneCAN or MAVLink"
  326. #endif
  327. bool have_location = false;
  328. const uint32_t last_location_ms = transport.get_last_location_ms();
  329. const uint32_t last_system_ms = transport.get_last_system_ms();
  330. led.update();
  331. status_reason = "";
  332. if (last_location_ms == 0 ||
  333. now_ms - last_location_ms > 5000) {
  334. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  335. }
  336. if (last_system_ms == 0 ||
  337. now_ms - last_system_ms > 5000) {
  338. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  339. }
  340. if (transport.get_parse_fail() != nullptr) {
  341. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  342. status_reason = String(transport.get_parse_fail());
  343. }
  344. // web update has to happen after we update Status above
  345. if (g.webserver_enable) {
  346. webif.update();
  347. }
  348. if (g.bcast_powerup) {
  349. // if we are broadcasting on powerup we always mark location valid
  350. // so the location with default data is sent
  351. if (!UAS_data.LocationValid) {
  352. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  353. UAS_data.LocationValid = 1;
  354. }
  355. } else {
  356. // only broadcast if we have received a location at least once
  357. if (last_location_ms == 0) {
  358. delay(1);
  359. return;
  360. }
  361. }
  362. set_data(transport);
  363. static uint32_t last_update_wifi_nan_ms;
  364. if (g.wifi_nan_rate > 0 &&
  365. now_ms - last_update_wifi_nan_ms > 1000/g.wifi_nan_rate) {
  366. last_update_wifi_nan_ms = now_ms;
  367. wifi.transmit_nan(UAS_data);
  368. }
  369. static uint32_t last_update_wifi_beacon_ms;
  370. if (g.wifi_beacon_rate > 0 &&
  371. now_ms - last_update_wifi_beacon_ms > 1000/g.wifi_beacon_rate) {
  372. last_update_wifi_beacon_ms = now_ms;
  373. wifi.transmit_beacon(UAS_data);
  374. }
  375. static uint32_t last_update_bt5_ms;
  376. if (g.bt5_rate > 0 &&
  377. now_ms - last_update_bt5_ms > 1000/g.bt5_rate) {
  378. last_update_bt5_ms = now_ms;
  379. ble.transmit_longrange(UAS_data);
  380. }
  381. static uint32_t last_update_bt4_ms;
  382. int bt4_states = UAS_data.BasicIDValid[1] ? 7 : 6;
  383. if (g.bt4_rate > 0 &&
  384. now_ms - last_update_bt4_ms > (1000.0f/bt4_states)/g.bt4_rate) {
  385. last_update_bt4_ms = now_ms;
  386. ble.transmit_legacy(UAS_data);
  387. }
  388. // sleep for a bit for power saving
  389. delay(1);
  390. }