RemoteIDModule.ino 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368
  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. static uint32_t last_location_ms;
  39. static WebInterface webif;
  40. #include "soc/soc.h"
  41. #include "soc/rtc_cntl_reg.h"
  42. static bool arm_check_ok = false; // goes true for LED arm check status
  43. static bool pfst_check_ok = false;
  44. /*
  45. setup serial ports
  46. */
  47. void setup()
  48. {
  49. // disable brownout checking
  50. WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
  51. g.init();
  52. led.set_state(Led::LedState::INIT);
  53. led.update();
  54. if (g.webserver_enable) {
  55. // need WiFi for web server
  56. wifi.init();
  57. }
  58. // Serial for debug printf
  59. Serial.begin(g.baudrate);
  60. // Serial1 for MAVLink
  61. Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
  62. // set all fields to invalid/initial values
  63. odid_initUasData(&UAS_data);
  64. #if AP_MAVLINK_ENABLED
  65. mavlink1.init();
  66. mavlink2.init();
  67. #endif
  68. #if AP_DRONECAN_ENABLED
  69. dronecan.init();
  70. #endif
  71. set_efuses();
  72. CheckFirmware::check_OTA_running();
  73. #if defined(PIN_CAN_EN)
  74. // optional CAN enable pin
  75. pinMode(PIN_CAN_EN, OUTPUT);
  76. digitalWrite(PIN_CAN_EN, HIGH);
  77. #endif
  78. #if defined(PIN_CAN_nSILENT)
  79. // disable silent pin
  80. pinMode(PIN_CAN_nSILENT, OUTPUT);
  81. digitalWrite(PIN_CAN_nSILENT, HIGH);
  82. #endif
  83. #if defined(PIN_CAN_TERM)
  84. // optional CAN termination control
  85. pinMode(PIN_CAN_TERM, OUTPUT);
  86. digitalWrite(PIN_CAN_TERM, HIGH);
  87. #endif
  88. pfst_check_ok = true; // note - this will need to be expanded to better capture PFST test status
  89. // initially set LED for fail
  90. led.set_state(Led::LedState::ARM_FAIL);
  91. esp_log_level_set("*", ESP_LOG_DEBUG);
  92. esp_ota_mark_app_valid_cancel_rollback();
  93. }
  94. #define IMIN(x,y) ((x)<(y)?(x):(y))
  95. #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
  96. /*
  97. check parsing of UAS_data, this checks ranges of values to ensure we
  98. will produce a valid pack
  99. */
  100. static const char *check_parse(void)
  101. {
  102. {
  103. ODID_Location_encoded encoded {};
  104. if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
  105. return "bad LOCATION data";
  106. }
  107. }
  108. {
  109. ODID_System_encoded encoded {};
  110. if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
  111. return "bad SYSTEM data";
  112. }
  113. }
  114. {
  115. ODID_BasicID_encoded encoded {};
  116. if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  117. return "bad BASIC_ID data";
  118. }
  119. }
  120. {
  121. ODID_SelfID_encoded encoded {};
  122. if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  123. return "bad SELF_ID data";
  124. }
  125. }
  126. {
  127. ODID_OperatorID_encoded encoded {};
  128. if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  129. return "bad OPERATOR_ID data";
  130. }
  131. }
  132. return nullptr;
  133. }
  134. /*
  135. fill in UAS_data from MAVLink packets
  136. */
  137. static void set_data(Transport &t)
  138. {
  139. const auto &operator_id = t.get_operator_id();
  140. const auto &basic_id = t.get_basic_id();
  141. const auto &system = t.get_system();
  142. const auto &self_id = t.get_self_id();
  143. const auto &location = t.get_location();
  144. /*
  145. if we don't have BasicID info from parameters and we have it
  146. from the DroneCAN or MAVLink transport then copy it to the
  147. parameters to persist it. This makes it possible to set the
  148. UAS_ID string via a MAVLink BASIC_ID message and also offers a
  149. migration path from the old approach of GCS setting these values
  150. to having them as parameters
  151. */
  152. if (!g.have_basic_id_info()) {
  153. if (basic_id.ua_type != 0 &&
  154. basic_id.id_type != 0 &&
  155. strnlen((const char *)basic_id.uas_id, 20) > 0) {
  156. g.set_by_name_uint8("UAS_TYPE", basic_id.ua_type);
  157. g.set_by_name_uint8("UAS_ID_TYPE", basic_id.id_type);
  158. char uas_id[21] {};
  159. ODID_COPY_STR(uas_id, basic_id.uas_id);
  160. g.set_by_name_string("UAS_ID", uas_id);
  161. }
  162. }
  163. // BasicID
  164. if (g.have_basic_id_info()) {
  165. // from parameters
  166. UAS_data.BasicID[0].UAType = (ODID_uatype_t)g.ua_type;
  167. UAS_data.BasicID[0].IDType = (ODID_idtype_t)g.id_type;
  168. ODID_COPY_STR(UAS_data.BasicID[0].UASID, g.uas_id);
  169. } else {
  170. // from transport
  171. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  172. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  173. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  174. }
  175. UAS_data.BasicIDValid[0] = 1;
  176. // OperatorID
  177. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  178. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  179. UAS_data.OperatorIDValid = 1;
  180. // SelfID
  181. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  182. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  183. UAS_data.SelfIDValid = 1;
  184. // System
  185. if (system.timestamp != 0) {
  186. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  187. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  188. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  189. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  190. UAS_data.System.AreaCount = system.area_count;
  191. UAS_data.System.AreaRadius = system.area_radius;
  192. UAS_data.System.AreaCeiling = system.area_ceiling;
  193. UAS_data.System.AreaFloor = system.area_floor;
  194. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  195. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  196. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  197. UAS_data.System.Timestamp = system.timestamp;
  198. UAS_data.SystemValid = 1;
  199. }
  200. // Location
  201. if (location.timestamp != 0) {
  202. UAS_data.Location.Status = (ODID_status_t)location.status;
  203. UAS_data.Location.Direction = location.direction*0.01;
  204. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  205. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  206. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  207. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  208. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  209. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  210. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  211. UAS_data.Location.Height = location.height;
  212. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  213. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  214. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  215. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  216. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  217. UAS_data.Location.TimeStamp = location.timestamp;
  218. UAS_data.LocationValid = 1;
  219. }
  220. const char *reason = check_parse();
  221. if (reason == nullptr) {
  222. t.arm_status_check(reason);
  223. }
  224. t.set_parse_fail(reason);
  225. arm_check_ok = (reason==nullptr);
  226. led.set_state(pfst_check_ok && arm_check_ok? Led::LedState::ARM_OK : Led::LedState::ARM_FAIL);
  227. uint32_t now_ms = millis();
  228. uint32_t location_age_ms = now_ms - t.get_last_location_ms();
  229. uint32_t last_location_age_ms = now_ms - last_location_ms;
  230. if (location_age_ms < last_location_age_ms) {
  231. last_location_ms = t.get_last_location_ms();
  232. }
  233. }
  234. static uint8_t loop_counter = 0;
  235. void loop()
  236. {
  237. #if AP_MAVLINK_ENABLED
  238. mavlink1.update();
  239. mavlink2.update();
  240. #endif
  241. #if AP_DRONECAN_ENABLED
  242. dronecan.update();
  243. #endif
  244. const uint32_t now_ms = millis();
  245. if (g.webserver_enable) {
  246. webif.update();
  247. }
  248. // the transports have common static data, so we can just use the
  249. // first for status
  250. #if AP_MAVLINK_ENABLED
  251. auto &transport = mavlink1;
  252. #elif AP_DRONECAN_ENABLED
  253. auto &transport = dronecan;
  254. #else
  255. #error "Must enable DroneCAN or MAVLink"
  256. #endif
  257. bool have_location = false;
  258. const uint32_t last_location_ms = transport.get_last_location_ms();
  259. const uint32_t last_system_ms = transport.get_last_system_ms();
  260. led.update();
  261. if (g.bcast_powerup) {
  262. // if we are broadcasting on powerup we always mark location valid
  263. // so the location with default data is sent
  264. if (!UAS_data.LocationValid) {
  265. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  266. UAS_data.LocationValid = 1;
  267. }
  268. } else {
  269. // only broadcast if we have received a location at least once
  270. if (last_location_ms == 0) {
  271. delay(1);
  272. return;
  273. }
  274. }
  275. if (last_location_ms == 0 ||
  276. now_ms - last_location_ms > 5000) {
  277. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  278. }
  279. if (last_system_ms == 0 ||
  280. now_ms - last_system_ms > 5000) {
  281. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  282. }
  283. if (transport.get_parse_fail() != nullptr) {
  284. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  285. }
  286. set_data(transport);
  287. static uint32_t last_update_wifi_nan_ms;
  288. if (g.wifi_nan_rate > 0 &&
  289. now_ms - last_update_wifi_nan_ms > 1000/g.wifi_nan_rate) {
  290. last_update_wifi_nan_ms = now_ms;
  291. wifi.transmit_nan(UAS_data);
  292. }
  293. static uint32_t last_update_wifi_beacon_ms;
  294. if (g.wifi_beacon_rate > 0 &&
  295. now_ms - last_update_wifi_beacon_ms > 1000/g.wifi_beacon_rate) {
  296. last_update_wifi_beacon_ms = now_ms;
  297. wifi.transmit_beacon(UAS_data);
  298. }
  299. static uint32_t last_update_bt5_ms;
  300. if (g.bt5_rate > 0 &&
  301. now_ms - last_update_bt5_ms > 1000/g.bt5_rate) {
  302. last_update_bt5_ms = now_ms;
  303. ble.transmit_longrange(UAS_data);
  304. }
  305. static uint32_t last_update_bt4_ms;
  306. if (g.bt4_rate > 0 &&
  307. now_ms - last_update_bt4_ms > 200/g.bt4_rate) {
  308. last_update_bt4_ms = now_ms;
  309. ble.transmit_legacy(UAS_data);
  310. ble.transmit_legacy_name(UAS_data);
  311. }
  312. // sleep for a bit for power saving
  313. delay(1);
  314. }