RemoteIDModule.ino 14 KB

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