RemoteIDModule.ino 9.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312
  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. /*
  119. fill in UAS_data from MAVLink packets
  120. */
  121. static void set_data(Transport &t)
  122. {
  123. const auto &operator_id = t.get_operator_id();
  124. const auto &basic_id = t.get_basic_id();
  125. const auto &system = t.get_system();
  126. const auto &self_id = t.get_self_id();
  127. const auto &location = t.get_location();
  128. // BasicID
  129. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  130. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  131. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  132. UAS_data.BasicIDValid[0] = 1;
  133. // OperatorID
  134. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  135. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  136. UAS_data.OperatorIDValid = 1;
  137. // SelfID
  138. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  139. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  140. UAS_data.SelfIDValid = 1;
  141. // System
  142. if (system.timestamp != 0) {
  143. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  144. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  145. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  146. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  147. UAS_data.System.AreaCount = system.area_count;
  148. UAS_data.System.AreaRadius = system.area_radius;
  149. UAS_data.System.AreaCeiling = system.area_ceiling;
  150. UAS_data.System.AreaFloor = system.area_floor;
  151. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  152. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  153. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  154. UAS_data.System.Timestamp = system.timestamp;
  155. UAS_data.SystemValid = 1;
  156. }
  157. // Location
  158. if (location.timestamp != 0) {
  159. UAS_data.Location.Status = (ODID_status_t)location.status;
  160. UAS_data.Location.Direction = location.direction*0.01;
  161. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  162. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  163. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  164. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  165. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  166. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  167. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  168. UAS_data.Location.Height = location.height;
  169. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  170. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  171. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  172. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  173. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  174. UAS_data.Location.TimeStamp = location.timestamp;
  175. UAS_data.LocationValid = 1;
  176. }
  177. const char *reason = check_parse();
  178. if (reason == nullptr) {
  179. t.arm_status_check(reason);
  180. }
  181. t.set_parse_fail(reason);
  182. #ifdef PIN_STATUS_LED
  183. // LED off if good to arm
  184. pinMode(PIN_STATUS_LED, OUTPUT);
  185. digitalWrite(PIN_STATUS_LED, reason==nullptr?!STATUS_LED_ON:STATUS_LED_ON);
  186. #endif
  187. uint32_t now_ms = millis();
  188. uint32_t location_age_ms = now_ms - t.get_last_location_ms();
  189. uint32_t last_location_age_ms = now_ms - last_location_ms;
  190. if (location_age_ms < last_location_age_ms) {
  191. last_location_ms = t.get_last_location_ms();
  192. }
  193. }
  194. static uint8_t loop_counter = 0;
  195. void loop()
  196. {
  197. #if AP_MAVLINK_ENABLED
  198. mavlink1.update();
  199. mavlink2.update();
  200. #endif
  201. #if AP_DRONECAN_ENABLED
  202. dronecan.update();
  203. #endif
  204. const uint32_t now_ms = millis();
  205. if (g.webserver_enable) {
  206. webif.update();
  207. }
  208. // the transports have common static data, so we can just use the
  209. // first for status
  210. #if AP_MAVLINK_ENABLED
  211. auto &transport = mavlink1;
  212. #elif AP_DRONECAN_ENABLED
  213. auto &transport = dronecan;
  214. #else
  215. #error "Must enable DroneCAN or MAVLink"
  216. #endif
  217. bool have_location = false;
  218. const uint32_t last_location_ms = transport.get_last_location_ms();
  219. const uint32_t last_system_ms = transport.get_last_system_ms();
  220. if (g.bcast_powerup) {
  221. // if we are broadcasting on powerup we always mark location valid
  222. // so the location with default data is sent
  223. if (!UAS_data.LocationValid) {
  224. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  225. UAS_data.LocationValid = 1;
  226. }
  227. } else {
  228. // only broadcast if we have received a location at least once
  229. if (last_location_ms == 0) {
  230. delay(1);
  231. return;
  232. }
  233. }
  234. if (last_location_ms == 0 ||
  235. now_ms - last_location_ms > 5000) {
  236. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  237. }
  238. if (last_system_ms == 0 ||
  239. now_ms - last_system_ms > 5000) {
  240. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  241. }
  242. if (transport.get_parse_fail() != nullptr) {
  243. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  244. }
  245. set_data(transport);
  246. static uint32_t last_update_wifi_ms;
  247. if (g.wifi_nan_rate > 0 &&
  248. now_ms - last_update_wifi_ms > 1000/g.wifi_nan_rate) {
  249. last_update_wifi_ms = now_ms;
  250. wifi.transmit(UAS_data);
  251. }
  252. static uint32_t last_update_bt5_ms;
  253. if (g.bt5_rate > 0 &&
  254. now_ms - last_update_bt5_ms > 1000/g.bt5_rate) {
  255. last_update_bt5_ms = now_ms;
  256. ble.transmit_longrange(UAS_data);
  257. }
  258. static uint32_t last_update_bt4_ms;
  259. if (g.bt4_rate > 0 &&
  260. now_ms - last_update_bt4_ms > 200/g.bt4_rate) {
  261. last_update_bt4_ms = now_ms;
  262. ble.transmit_legacy(UAS_data);
  263. ble.transmit_legacy_name(UAS_data);
  264. }
  265. // sleep for a bit for power saving
  266. delay(1);
  267. }