RemoteIDModule.ino 13 KB

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