RemoteIDModule.ino 9.5 KB

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