RemoteIDModule.ino 11 KB

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