RemoteIDModule.ino 9.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307
  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. #if AP_DRONECAN_ENABLED
  19. static DroneCAN dronecan;
  20. #endif
  21. #if AP_MAVLINK_ENABLED
  22. static MAVLinkSerial mavlink1{Serial1, MAVLINK_COMM_0};
  23. static MAVLinkSerial mavlink2{Serial, MAVLINK_COMM_1};
  24. #endif
  25. #if AP_WIFI_NAN_ENABLED
  26. static WiFi_NAN wifi;
  27. #endif
  28. #if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED
  29. static BLE_TX ble;
  30. #endif
  31. #define DEBUG_BAUDRATE 57600
  32. #define MAVLINK_BAUDRATE 57600
  33. // OpenDroneID output data structure
  34. static ODID_UAS_Data UAS_data;
  35. static uint32_t last_location_ms;
  36. /*
  37. setup serial ports
  38. */
  39. void setup()
  40. {
  41. // Serial for debug printf
  42. Serial.begin(DEBUG_BAUDRATE);
  43. // Serial1 for MAVLink
  44. Serial1.begin(MAVLINK_BAUDRATE, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
  45. // set all fields to invalid/initial values
  46. odid_initUasData(&UAS_data);
  47. #if AP_MAVLINK_ENABLED
  48. mavlink1.init();
  49. mavlink2.init();
  50. #endif
  51. #if AP_DRONECAN_ENABLED
  52. dronecan.init();
  53. #endif
  54. #if AP_WIFI_NAN_ENABLED
  55. wifi.init();
  56. #endif
  57. #if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED
  58. ble.init();
  59. #endif
  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. }
  76. #define IMIN(x,y) ((x)<(y)?(x):(y))
  77. #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
  78. /*
  79. check parsing of UAS_data, this checks ranges of values to ensure we
  80. will produce a valid pack
  81. */
  82. static const char *check_parse(void)
  83. {
  84. {
  85. ODID_Location_encoded encoded {};
  86. if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
  87. return "bad LOCATION data";
  88. }
  89. }
  90. {
  91. ODID_System_encoded encoded {};
  92. if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
  93. return "bad SYSTEM data";
  94. }
  95. }
  96. {
  97. ODID_BasicID_encoded encoded {};
  98. if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  99. return "bad BASIC_ID data";
  100. }
  101. }
  102. {
  103. ODID_SelfID_encoded encoded {};
  104. if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  105. return "bad SELF_ID data";
  106. }
  107. }
  108. {
  109. ODID_OperatorID_encoded encoded {};
  110. if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  111. return "bad OPERATOR_ID data";
  112. }
  113. }
  114. return nullptr;
  115. }
  116. /*
  117. fill in UAS_data from MAVLink packets
  118. */
  119. static void set_data(Transport &t)
  120. {
  121. const auto &operator_id = t.get_operator_id();
  122. const auto &basic_id = t.get_basic_id();
  123. const auto &system = t.get_system();
  124. const auto &self_id = t.get_self_id();
  125. const auto &location = t.get_location();
  126. // BasicID
  127. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  128. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  129. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  130. UAS_data.BasicIDValid[0] = 1;
  131. // OperatorID
  132. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  133. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  134. UAS_data.OperatorIDValid = 1;
  135. // SelfID
  136. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  137. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  138. UAS_data.SelfIDValid = 1;
  139. // System
  140. if (system.timestamp != 0) {
  141. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  142. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  143. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  144. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  145. UAS_data.System.AreaCount = system.area_count;
  146. UAS_data.System.AreaRadius = system.area_radius;
  147. UAS_data.System.AreaCeiling = system.area_ceiling;
  148. UAS_data.System.AreaFloor = system.area_floor;
  149. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  150. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  151. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  152. UAS_data.System.Timestamp = system.timestamp;
  153. UAS_data.SystemValid = 1;
  154. }
  155. // Location
  156. if (location.timestamp != 0) {
  157. UAS_data.Location.Status = (ODID_status_t)location.status;
  158. UAS_data.Location.Direction = location.direction*0.01;
  159. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  160. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  161. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  162. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  163. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  164. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  165. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  166. UAS_data.Location.Height = location.height;
  167. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  168. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  169. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  170. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  171. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  172. UAS_data.Location.TimeStamp = location.timestamp;
  173. UAS_data.LocationValid = 1;
  174. }
  175. const char *reason = check_parse();
  176. if (reason == nullptr) {
  177. t.arm_status_check(reason);
  178. }
  179. t.set_parse_fail(reason);
  180. #ifdef PIN_STATUS_LED
  181. // LED off if good to arm
  182. pinMode(PIN_STATUS_LED, OUTPUT);
  183. digitalWrite(PIN_STATUS_LED, reason==nullptr?!STATUS_LED_ON:STATUS_LED_ON);
  184. #endif
  185. uint32_t now_ms = millis();
  186. uint32_t location_age_ms = now_ms - t.get_last_location_ms();
  187. uint32_t last_location_age_ms = now_ms - last_location_ms;
  188. if (location_age_ms < last_location_age_ms) {
  189. last_location_ms = t.get_last_location_ms();
  190. }
  191. }
  192. static uint8_t loop_counter = 0;
  193. void loop()
  194. {
  195. static uint32_t last_update;
  196. #if AP_MAVLINK_ENABLED
  197. mavlink1.update();
  198. mavlink2.update();
  199. #endif
  200. #if AP_DRONECAN_ENABLED
  201. dronecan.update();
  202. #endif
  203. const uint32_t now_ms = millis();
  204. // we call BT4 send at 5x the desired rate as it has to split the pkts 5 ways
  205. const uint32_t rate_divider = 5;
  206. if (now_ms - last_update < 1000UL/(OUTPUT_RATE_HZ*rate_divider)) {
  207. // not ready for a new frame yet
  208. return;
  209. }
  210. loop_counter++;
  211. loop_counter %= rate_divider;
  212. // the transports have common static data, so we can just use the
  213. // first for status
  214. #if AP_MAVLINK_ENABLED
  215. auto &transport = mavlink1;
  216. #elif AP_DRONECAN_ENABLED
  217. auto &transport = dronecan;
  218. #else
  219. #error "Must enable DroneCAN or MAVLink"
  220. #endif
  221. bool have_location = false;
  222. const uint32_t last_location_ms = transport.get_last_location_ms();
  223. const uint32_t last_system_ms = transport.get_last_system_ms();
  224. #if AP_BROADCAST_ON_POWER_UP
  225. // if we are broadcasting on powerup we always mark location valid
  226. // so the location with default data is sent
  227. if (!UAS_data.LocationValid) {
  228. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  229. UAS_data.LocationValid = 1;
  230. }
  231. #else
  232. // only broadcast if we have received a location at least once
  233. if (last_location_ms == 0) {
  234. return;
  235. }
  236. #endif
  237. if (last_location_ms == 0 ||
  238. now_ms - last_location_ms > 5000) {
  239. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  240. }
  241. if (last_system_ms == 0 ||
  242. now_ms - last_system_ms > 5000) {
  243. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  244. }
  245. if (transport.get_parse_fail() != nullptr) {
  246. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  247. }
  248. set_data(transport);
  249. last_update = now_ms;
  250. #if AP_WIFI_NAN_ENABLED
  251. if (loop_counter == 0) { //only run on the original update rate
  252. wifi.transmit(UAS_data);
  253. }
  254. #endif
  255. #if AP_BLE_LONGRANGE_ENABLED
  256. if (loop_counter == 0) { //only run on the original update rate
  257. ble.transmit_longrange(UAS_data);
  258. }
  259. #endif
  260. #if AP_BLE_LEGACY_ENABLED
  261. ble.transmit_legacy(UAS_data);
  262. #endif
  263. #if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED
  264. ble.transmit_legacy_name(UAS_data);
  265. #endif
  266. }