RemoteIDModule.ino 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357
  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 "parameters.h"
  19. #include "webinterface.h"
  20. #include "check_firmware.h"
  21. #include <esp_ota_ops.h>
  22. #include "efuse.h"
  23. #if AP_DRONECAN_ENABLED
  24. static DroneCAN dronecan;
  25. #endif
  26. #if AP_MAVLINK_ENABLED
  27. static MAVLinkSerial mavlink1{Serial1, MAVLINK_COMM_0};
  28. static MAVLinkSerial mavlink2{Serial, MAVLINK_COMM_1};
  29. #endif
  30. static WiFi_NAN wifi;
  31. static BLE_TX ble;
  32. #define DEBUG_BAUDRATE 57600
  33. // OpenDroneID output data structure
  34. ODID_UAS_Data UAS_data;
  35. static uint32_t last_location_ms;
  36. static WebInterface webif;
  37. #include "soc/soc.h"
  38. #include "soc/rtc_cntl_reg.h"
  39. static uint32_t last_led_trig_ms;
  40. static bool arm_check_ok = false; // goes true for LED arm check status
  41. static bool pfst_check_ok = false;
  42. /*
  43. setup serial ports
  44. */
  45. void setup()
  46. {
  47. // disable brownout checking
  48. WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
  49. g.init();
  50. // Serial for debug printf
  51. Serial.begin(g.baudrate);
  52. // Serial1 for MAVLink
  53. Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
  54. // set all fields to invalid/initial values
  55. odid_initUasData(&UAS_data);
  56. #if AP_MAVLINK_ENABLED
  57. mavlink1.init();
  58. mavlink2.init();
  59. #endif
  60. #if AP_DRONECAN_ENABLED
  61. dronecan.init();
  62. #endif
  63. set_efuses();
  64. CheckFirmware::check_OTA_running();
  65. #if defined(PIN_CAN_EN)
  66. // optional CAN enable pin
  67. pinMode(PIN_CAN_EN, OUTPUT);
  68. digitalWrite(PIN_CAN_EN, HIGH);
  69. #endif
  70. #if defined(PIN_CAN_nSILENT)
  71. // disable silent pin
  72. pinMode(PIN_CAN_nSILENT, OUTPUT);
  73. digitalWrite(PIN_CAN_nSILENT, HIGH);
  74. #endif
  75. #if defined(PIN_CAN_TERM)
  76. // optional CAN termination control
  77. pinMode(PIN_CAN_TERM, OUTPUT);
  78. digitalWrite(PIN_CAN_TERM, HIGH);
  79. #endif
  80. #ifdef PIN_STATUS_LED
  81. // LED off if good to arm
  82. pfst_check_ok = true; // note - this will need to be expanded to better capture PFST test status
  83. pinMode(PIN_STATUS_LED, OUTPUT);
  84. #endif
  85. esp_log_level_set("*", ESP_LOG_DEBUG);
  86. esp_ota_mark_app_valid_cancel_rollback();
  87. }
  88. #define IMIN(x,y) ((x)<(y)?(x):(y))
  89. #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
  90. /*
  91. check parsing of UAS_data, this checks ranges of values to ensure we
  92. will produce a valid pack
  93. */
  94. static const char *check_parse(void)
  95. {
  96. {
  97. ODID_Location_encoded encoded {};
  98. if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
  99. return "bad LOCATION data";
  100. }
  101. }
  102. {
  103. ODID_System_encoded encoded {};
  104. if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
  105. return "bad SYSTEM data";
  106. }
  107. }
  108. {
  109. ODID_BasicID_encoded encoded {};
  110. if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  111. return "bad BASIC_ID data";
  112. }
  113. }
  114. {
  115. ODID_SelfID_encoded encoded {};
  116. if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  117. return "bad SELF_ID data";
  118. }
  119. }
  120. {
  121. ODID_OperatorID_encoded encoded {};
  122. if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  123. return "bad OPERATOR_ID data";
  124. }
  125. }
  126. return nullptr;
  127. }
  128. /*
  129. fill in UAS_data from MAVLink packets
  130. */
  131. static void set_data(Transport &t)
  132. {
  133. const auto &operator_id = t.get_operator_id();
  134. const auto &basic_id = t.get_basic_id();
  135. const auto &system = t.get_system();
  136. const auto &self_id = t.get_self_id();
  137. const auto &location = t.get_location();
  138. // BasicID
  139. if (g.have_basic_id_info()) {
  140. // from parameters
  141. UAS_data.BasicID[0].UAType = (ODID_uatype_t)g.ua_type;
  142. UAS_data.BasicID[0].IDType = (ODID_idtype_t)g.id_type;
  143. ODID_COPY_STR(UAS_data.BasicID[0].UASID, g.uas_id);
  144. } else {
  145. // from transport
  146. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  147. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  148. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  149. }
  150. UAS_data.BasicIDValid[0] = 1;
  151. // OperatorID
  152. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  153. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  154. UAS_data.OperatorIDValid = 1;
  155. // SelfID
  156. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  157. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  158. UAS_data.SelfIDValid = 1;
  159. // System
  160. if (system.timestamp != 0) {
  161. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  162. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  163. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  164. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  165. UAS_data.System.AreaCount = system.area_count;
  166. UAS_data.System.AreaRadius = system.area_radius;
  167. UAS_data.System.AreaCeiling = system.area_ceiling;
  168. UAS_data.System.AreaFloor = system.area_floor;
  169. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  170. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  171. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  172. UAS_data.System.Timestamp = system.timestamp;
  173. UAS_data.SystemValid = 1;
  174. }
  175. // Location
  176. if (location.timestamp != 0) {
  177. UAS_data.Location.Status = (ODID_status_t)location.status;
  178. UAS_data.Location.Direction = location.direction*0.01;
  179. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  180. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  181. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  182. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  183. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  184. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  185. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  186. UAS_data.Location.Height = location.height;
  187. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  188. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  189. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  190. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  191. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  192. UAS_data.Location.TimeStamp = location.timestamp;
  193. UAS_data.LocationValid = 1;
  194. }
  195. const char *reason = check_parse();
  196. if (reason == nullptr) {
  197. t.arm_status_check(reason);
  198. }
  199. t.set_parse_fail(reason);
  200. arm_check_ok = (reason==nullptr);
  201. uint32_t now_ms = millis();
  202. uint32_t location_age_ms = now_ms - t.get_last_location_ms();
  203. uint32_t last_location_age_ms = now_ms - last_location_ms;
  204. if (location_age_ms < last_location_age_ms) {
  205. last_location_ms = t.get_last_location_ms();
  206. }
  207. }
  208. void set_output_led(uint32_t _now) {
  209. #ifdef PIN_STATUS_LED
  210. #ifdef LED_MODE_FLASH
  211. // LED off if good to arm
  212. //pinMode(PIN_STATUS_LED, OUTPUT);
  213. if (arm_check_ok && pfst_check_ok) {
  214. digitalWrite(PIN_STATUS_LED, STATUS_LED_ON);
  215. last_led_trig_ms = 0;
  216. } else if (!arm_check_ok && pfst_check_ok) {
  217. if (_now - last_led_trig_ms > 100) {
  218. digitalWrite(PIN_STATUS_LED,!digitalRead(PIN_STATUS_LED));
  219. last_led_trig_ms = _now;
  220. }
  221. } else {
  222. digitalWrite(PIN_STATUS_LED, STATUS_LED_ON);
  223. last_led_trig_ms = 0;
  224. }
  225. #else
  226. // Default LED Behavior
  227. digitalWrite(PIN_STATUS_LED,arm_check_ok?!STATUS_LED_ON:STATUS_LED_ON);
  228. #endif // LED_MODE_FLASH
  229. #endif // PIN_STATUS_LED
  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. if (g.bcast_powerup) {
  258. // if we are broadcasting on powerup we always mark location valid
  259. // so the location with default data is sent
  260. if (!UAS_data.LocationValid) {
  261. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  262. UAS_data.LocationValid = 1;
  263. }
  264. } else {
  265. // only broadcast if we have received a location at least once
  266. if (last_location_ms == 0) {
  267. delay(1);
  268. return;
  269. }
  270. }
  271. if (last_location_ms == 0 ||
  272. now_ms - last_location_ms > 5000) {
  273. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  274. }
  275. if (last_system_ms == 0 ||
  276. now_ms - last_system_ms > 5000) {
  277. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  278. }
  279. if (transport.get_parse_fail() != nullptr) {
  280. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  281. }
  282. set_data(transport);
  283. static uint32_t last_update_wifi_ms;
  284. if (g.wifi_nan_rate > 0 &&
  285. now_ms - last_update_wifi_ms > 1000/g.wifi_nan_rate) {
  286. last_update_wifi_ms = now_ms;
  287. wifi.transmit(UAS_data);
  288. }
  289. static uint32_t last_update_bt5_ms;
  290. if (g.bt5_rate > 0 &&
  291. now_ms - last_update_bt5_ms > 1000/g.bt5_rate) {
  292. last_update_bt5_ms = now_ms;
  293. ble.transmit_longrange(UAS_data);
  294. }
  295. static uint32_t last_update_bt4_ms;
  296. if (g.bt4_rate > 0 &&
  297. now_ms - last_update_bt4_ms > 200/g.bt4_rate) {
  298. last_update_bt4_ms = now_ms;
  299. ble.transmit_legacy(UAS_data);
  300. ble.transmit_legacy_name(UAS_data);
  301. }
  302. #ifdef PIN_STATUS_LED
  303. set_output_led(now_ms);
  304. #endif
  305. // sleep for a bit for power saving
  306. delay(1);
  307. }