RemoteIDModule.ino 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395
  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. #if AP_DRONECAN_ENABLED
  23. static DroneCAN dronecan;
  24. #endif
  25. #if AP_MAVLINK_ENABLED
  26. static MAVLinkSerial mavlink1{Serial1, MAVLINK_COMM_0};
  27. static MAVLinkSerial mavlink2{Serial, MAVLINK_COMM_1};
  28. #endif
  29. static WiFi_NAN wifi;
  30. static BLE_TX ble;
  31. #define DEBUG_BAUDRATE 57600
  32. // OpenDroneID output data structure
  33. static ODID_UAS_Data UAS_data;
  34. static uint32_t last_location_ms;
  35. static WebInterface webif;
  36. #include "soc/soc.h"
  37. #include "soc/rtc_cntl_reg.h"
  38. /*
  39. setup serial ports
  40. */
  41. void setup()
  42. {
  43. // disable brownout checking
  44. WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
  45. g.init();
  46. // Serial for debug printf
  47. Serial.begin(g.baudrate);
  48. // Serial1 for MAVLink
  49. Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
  50. // set all fields to invalid/initial values
  51. odid_initUasData(&UAS_data);
  52. #if AP_MAVLINK_ENABLED
  53. mavlink1.init();
  54. mavlink2.init();
  55. #endif
  56. #if AP_DRONECAN_ENABLED
  57. dronecan.init();
  58. #endif
  59. CheckFirmware::check_OTA_running();
  60. #if defined(PIN_CAN_EN)
  61. // optional CAN enable pin
  62. pinMode(PIN_CAN_EN, OUTPUT);
  63. digitalWrite(PIN_CAN_EN, HIGH);
  64. #endif
  65. #if defined(PIN_CAN_nSILENT)
  66. // disable silent pin
  67. pinMode(PIN_CAN_nSILENT, OUTPUT);
  68. digitalWrite(PIN_CAN_nSILENT, HIGH);
  69. #endif
  70. #if defined(PIN_CAN_TERM)
  71. // optional CAN termination control
  72. pinMode(PIN_CAN_TERM, OUTPUT);
  73. digitalWrite(PIN_CAN_TERM, HIGH);
  74. #endif
  75. esp_log_level_set("*", ESP_LOG_DEBUG);
  76. esp_ota_mark_app_valid_cancel_rollback();
  77. }
  78. #define IMIN(x,y) ((x)<(y)?(x):(y))
  79. #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
  80. /*
  81. check parsing of UAS_data, this checks ranges of values to ensure we
  82. will produce a valid pack
  83. */
  84. static const char *check_parse(void)
  85. {
  86. {
  87. ODID_Location_encoded encoded {};
  88. if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
  89. return "bad LOCATION data";
  90. }
  91. }
  92. {
  93. ODID_System_encoded encoded {};
  94. if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
  95. return "bad SYSTEM data";
  96. }
  97. }
  98. {
  99. ODID_BasicID_encoded encoded {};
  100. if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  101. return "bad BASIC_ID data";
  102. }
  103. }
  104. {
  105. ODID_SelfID_encoded encoded {};
  106. if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  107. return "bad SELF_ID data";
  108. }
  109. }
  110. {
  111. ODID_OperatorID_encoded encoded {};
  112. if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  113. return "bad OPERATOR_ID data";
  114. }
  115. }
  116. return nullptr;
  117. }
  118. static String escape_string(String s)
  119. {
  120. s.replace("\"", "");
  121. return s;
  122. }
  123. /*
  124. create a json string from a table
  125. */
  126. static String json_format(const json_table_t *table, uint8_t n)
  127. {
  128. String s = "{";
  129. for (uint8_t i=0; i<n; i++) {
  130. const auto &t = table[i];
  131. s += "\"" + t.name + "\" : ";
  132. s += "\"" + escape_string(t.value) + "\"";
  133. if (i != n-1) {
  134. s += ",";
  135. }
  136. }
  137. s += "}";
  138. return s;
  139. }
  140. #define ARRAY_SIZE(a) (sizeof(a) / sizeof(a[0]))
  141. String status_json(void)
  142. {
  143. const uint32_t now_s = millis() / 1000;
  144. const uint32_t sec = now_s % 60;
  145. const uint32_t min = (now_s / 60) % 60;
  146. const uint32_t hr = (now_s / 3600) % 24;
  147. const json_table_t table[] = {
  148. { "STATUS:VERSION", String(FW_VERSION_MAJOR) + "." + String(FW_VERSION_MINOR) },
  149. { "STATUS:UPTIME", String(hr) + ":" + String(min) + ":" + String(sec) },
  150. { "STATUS:FREEMEM", String(ESP.getFreeHeap()) },
  151. { "BASICID:UAType", String(UAS_data.BasicID[0].UAType) },
  152. { "BASICID:IDType", String(UAS_data.BasicID[0].IDType) },
  153. { "BASICID:UASID", String(UAS_data.BasicID[0].UASID) },
  154. { "OPERATORID:IDType", String(UAS_data.OperatorID.OperatorIdType) },
  155. { "OPERATORID:ID", String(UAS_data.OperatorID.OperatorId) },
  156. { "SELFID:DescType", String(UAS_data.SelfID.DescType) },
  157. { "SELFID:Desc", String(UAS_data.SelfID.Desc) },
  158. { "SYSTEM:OperatorLocationType", String(UAS_data.System.OperatorLocationType) },
  159. { "SYSTEM:ClassificationType", String(UAS_data.System.ClassificationType) },
  160. { "SYSTEM:OperatorLatitude", String(UAS_data.System.OperatorLatitude) },
  161. { "SYSTEM:OperatorLongitude", String(UAS_data.System.OperatorLongitude) },
  162. { "SYSTEM:AreaCount", String(UAS_data.System.AreaCount) },
  163. { "SYSTEM:AreaRadius", String(UAS_data.System.AreaRadius) },
  164. { "SYSTEM:AreaCeiling", String(UAS_data.System.AreaCeiling) },
  165. { "SYSTEM:AreaFloor", String(UAS_data.System.AreaFloor) },
  166. { "SYSTEM:CategoryEU", String(UAS_data.System.CategoryEU) },
  167. { "SYSTEM:ClassEU", String(UAS_data.System.ClassEU) },
  168. { "SYSTEM:OperatorAltitudeGeo", String(UAS_data.System.OperatorAltitudeGeo) },
  169. { "SYSTEM:Timestamp", String(UAS_data.System.Timestamp) },
  170. { "LOCATION:Status", String(UAS_data.Location.Status) },
  171. { "LOCATION:Direction", String(UAS_data.Location.Direction) },
  172. { "LOCATION:SpeedHorizontal", String(UAS_data.Location.SpeedHorizontal) },
  173. { "LOCATION:SpeedVertical", String(UAS_data.Location.SpeedVertical) },
  174. { "LOCATION:Latitude", String(UAS_data.Location.Latitude) },
  175. { "LOCATION:Longitude", String(UAS_data.Location.Longitude) },
  176. { "LOCATION:AltitudeBaro", String(UAS_data.Location.AltitudeBaro) },
  177. { "LOCATION:AltitudeGeo", String(UAS_data.Location.AltitudeGeo) },
  178. { "LOCATION:HeightType", String(UAS_data.Location.HeightType) },
  179. { "LOCATION:Height", String(UAS_data.Location.Height) },
  180. { "LOCATION:HorizAccuracy", String(UAS_data.Location.HorizAccuracy) },
  181. { "LOCATION:VertAccuracy", String(UAS_data.Location.VertAccuracy) },
  182. { "LOCATION:BaroAccuracy", String(UAS_data.Location.BaroAccuracy) },
  183. { "LOCATION:SpeedAccuracy", String(UAS_data.Location.SpeedAccuracy) },
  184. { "LOCATION:TSAccuracy", String(UAS_data.Location.TSAccuracy) },
  185. { "LOCATION:TimeStamp", String(UAS_data.Location.TimeStamp) },
  186. };
  187. return json_format(table, ARRAY_SIZE(table));
  188. }
  189. /*
  190. fill in UAS_data from MAVLink packets
  191. */
  192. static void set_data(Transport &t)
  193. {
  194. const auto &operator_id = t.get_operator_id();
  195. const auto &basic_id = t.get_basic_id();
  196. const auto &system = t.get_system();
  197. const auto &self_id = t.get_self_id();
  198. const auto &location = t.get_location();
  199. // BasicID
  200. if (g.have_basic_id_info()) {
  201. // from parameters
  202. UAS_data.BasicID[0].UAType = (ODID_uatype_t)g.ua_type;
  203. UAS_data.BasicID[0].IDType = (ODID_idtype_t)g.id_type;
  204. ODID_COPY_STR(UAS_data.BasicID[0].UASID, g.uas_id);
  205. } else {
  206. // from transport
  207. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  208. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  209. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  210. }
  211. UAS_data.BasicIDValid[0] = 1;
  212. // OperatorID
  213. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  214. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  215. UAS_data.OperatorIDValid = 1;
  216. // SelfID
  217. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  218. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  219. UAS_data.SelfIDValid = 1;
  220. // System
  221. if (system.timestamp != 0) {
  222. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  223. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  224. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  225. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  226. UAS_data.System.AreaCount = system.area_count;
  227. UAS_data.System.AreaRadius = system.area_radius;
  228. UAS_data.System.AreaCeiling = system.area_ceiling;
  229. UAS_data.System.AreaFloor = system.area_floor;
  230. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  231. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  232. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  233. UAS_data.System.Timestamp = system.timestamp;
  234. UAS_data.SystemValid = 1;
  235. }
  236. // Location
  237. if (location.timestamp != 0) {
  238. UAS_data.Location.Status = (ODID_status_t)location.status;
  239. UAS_data.Location.Direction = location.direction*0.01;
  240. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  241. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  242. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  243. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  244. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  245. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  246. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  247. UAS_data.Location.Height = location.height;
  248. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  249. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  250. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  251. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  252. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  253. UAS_data.Location.TimeStamp = location.timestamp;
  254. UAS_data.LocationValid = 1;
  255. }
  256. const char *reason = check_parse();
  257. if (reason == nullptr) {
  258. t.arm_status_check(reason);
  259. }
  260. t.set_parse_fail(reason);
  261. #ifdef PIN_STATUS_LED
  262. // LED off if good to arm
  263. pinMode(PIN_STATUS_LED, OUTPUT);
  264. digitalWrite(PIN_STATUS_LED, reason==nullptr?!STATUS_LED_ON:STATUS_LED_ON);
  265. #endif
  266. uint32_t now_ms = millis();
  267. uint32_t location_age_ms = now_ms - t.get_last_location_ms();
  268. uint32_t last_location_age_ms = now_ms - last_location_ms;
  269. if (location_age_ms < last_location_age_ms) {
  270. last_location_ms = t.get_last_location_ms();
  271. }
  272. }
  273. static uint8_t loop_counter = 0;
  274. void loop()
  275. {
  276. #if AP_MAVLINK_ENABLED
  277. mavlink1.update();
  278. mavlink2.update();
  279. #endif
  280. #if AP_DRONECAN_ENABLED
  281. dronecan.update();
  282. #endif
  283. const uint32_t now_ms = millis();
  284. if (g.webserver_enable) {
  285. webif.update();
  286. }
  287. // the transports have common static data, so we can just use the
  288. // first for status
  289. #if AP_MAVLINK_ENABLED
  290. auto &transport = mavlink1;
  291. #elif AP_DRONECAN_ENABLED
  292. auto &transport = dronecan;
  293. #else
  294. #error "Must enable DroneCAN or MAVLink"
  295. #endif
  296. bool have_location = false;
  297. const uint32_t last_location_ms = transport.get_last_location_ms();
  298. const uint32_t last_system_ms = transport.get_last_system_ms();
  299. if (g.bcast_powerup) {
  300. // if we are broadcasting on powerup we always mark location valid
  301. // so the location with default data is sent
  302. if (!UAS_data.LocationValid) {
  303. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  304. UAS_data.LocationValid = 1;
  305. }
  306. } else {
  307. // only broadcast if we have received a location at least once
  308. if (last_location_ms == 0) {
  309. delay(1);
  310. return;
  311. }
  312. }
  313. if (last_location_ms == 0 ||
  314. now_ms - last_location_ms > 5000) {
  315. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  316. }
  317. if (last_system_ms == 0 ||
  318. now_ms - last_system_ms > 5000) {
  319. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  320. }
  321. if (transport.get_parse_fail() != nullptr) {
  322. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  323. }
  324. set_data(transport);
  325. static uint32_t last_update_wifi_ms;
  326. if (g.wifi_nan_rate > 0 &&
  327. now_ms - last_update_wifi_ms > 1000/g.wifi_nan_rate) {
  328. last_update_wifi_ms = now_ms;
  329. wifi.transmit(UAS_data);
  330. }
  331. static uint32_t last_update_bt5_ms;
  332. if (g.bt5_rate > 0 &&
  333. now_ms - last_update_bt5_ms > 1000/g.bt5_rate) {
  334. last_update_bt5_ms = now_ms;
  335. ble.transmit_longrange(UAS_data);
  336. }
  337. static uint32_t last_update_bt4_ms;
  338. if (g.bt4_rate > 0 &&
  339. now_ms - last_update_bt4_ms > 200/g.bt4_rate) {
  340. last_update_bt4_ms = now_ms;
  341. ble.transmit_legacy(UAS_data);
  342. ble.transmit_legacy_name(UAS_data);
  343. }
  344. // sleep for a bit for power saving
  345. delay(1);
  346. }