RemoteIDModule.ino 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276
  1. /*
  2. implement OpenDroneID MAVLink and DroneCAN support
  3. */
  4. /*
  5. released under GNU GPL v3 or later
  6. */
  7. #include <Arduino.h>
  8. #include "version.h"
  9. #include <math.h>
  10. #include <time.h>
  11. #include <sys/time.h>
  12. #include <opendroneid.h>
  13. #include "board_config.h"
  14. #include "options.h"
  15. #include "mavlink.h"
  16. #include "DroneCAN.h"
  17. #include "WiFi_TX.h"
  18. #include "BLE_TX.h"
  19. #if AP_DRONECAN_ENABLED
  20. static DroneCAN dronecan;
  21. #endif
  22. #if AP_MAVLINK_ENABLED
  23. static MAVLinkSerial mavlink1{Serial1, MAVLINK_COMM_0};
  24. static MAVLinkSerial mavlink2{Serial, MAVLINK_COMM_1};
  25. #endif
  26. #if AP_WIFI_NAN_ENABLED
  27. static WiFi_NAN wifi;
  28. #endif
  29. #if AP_BLE_ENABLED
  30. static BLE_TX ble;
  31. #endif
  32. #define OUTPUT_RATE_HZ 5
  33. #define DEBUG_BAUDRATE 57600
  34. #define MAVLINK_BAUDRATE 57600
  35. // OpenDroneID output data structure
  36. static ODID_UAS_Data UAS_data;
  37. static uint32_t last_location_ms;
  38. /*
  39. setup serial ports
  40. */
  41. void setup()
  42. {
  43. // Serial for debug printf
  44. Serial.begin(DEBUG_BAUDRATE);
  45. Serial.printf("ArduRemoteID version %u.%u %08x\n",
  46. FW_VERSION_MAJOR, FW_VERSION_MINOR, GIT_VERSION);
  47. // Serial1 for MAVLink
  48. Serial1.begin(MAVLINK_BAUDRATE, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
  49. // set all fields to invalid/initial values
  50. odid_initUasData(&UAS_data);
  51. #if AP_MAVLINK_ENABLED
  52. mavlink1.init();
  53. mavlink2.init();
  54. #endif
  55. #if AP_DRONECAN_ENABLED
  56. dronecan.init();
  57. #endif
  58. #if AP_WIFI_NAN_ENABLED
  59. wifi.init();
  60. #endif
  61. #if AP_BLE_ENABLED
  62. ble.init();
  63. #endif
  64. #if defined(PIN_CAN_EN)
  65. // optional CAN enable pin
  66. pinMode(PIN_CAN_EN, OUTPUT);
  67. digitalWrite(PIN_CAN_EN, HIGH);
  68. #endif
  69. #if defined(PIN_CAN_nSILENT)
  70. // disable silent pin
  71. pinMode(PIN_CAN_nSILENT, OUTPUT);
  72. digitalWrite(PIN_CAN_nSILENT, HIGH);
  73. #endif
  74. #if defined(PIN_CAN_TERM)
  75. // optional CAN termination control
  76. pinMode(PIN_CAN_TERM, OUTPUT);
  77. digitalWrite(PIN_CAN_TERM, HIGH);
  78. #endif
  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. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  132. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  133. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  134. UAS_data.BasicIDValid[0] = 1;
  135. // OperatorID
  136. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  137. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  138. UAS_data.OperatorIDValid = 1;
  139. // SelfID
  140. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  141. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  142. UAS_data.SelfIDValid = 1;
  143. // System
  144. if (system.timestamp != 0) {
  145. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  146. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  147. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  148. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  149. UAS_data.System.AreaCount = system.area_count;
  150. UAS_data.System.AreaRadius = system.area_radius;
  151. UAS_data.System.AreaCeiling = system.area_ceiling;
  152. UAS_data.System.AreaFloor = system.area_floor;
  153. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  154. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  155. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  156. UAS_data.System.Timestamp = system.timestamp;
  157. UAS_data.SystemValid = 1;
  158. }
  159. // Location
  160. if (location.timestamp != 0) {
  161. UAS_data.Location.Status = (ODID_status_t)location.status;
  162. UAS_data.Location.Direction = location.direction*0.01;
  163. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  164. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  165. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  166. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  167. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  168. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  169. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  170. UAS_data.Location.Height = location.height;
  171. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  172. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  173. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  174. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  175. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  176. UAS_data.Location.TimeStamp = location.timestamp;
  177. UAS_data.LocationValid = 1;
  178. }
  179. const char *reason = check_parse();
  180. if (reason == nullptr) {
  181. t.arm_status_check(reason);
  182. }
  183. t.set_parse_fail(reason);
  184. #ifdef PIN_STATUS_LED
  185. // LED off if good to arm
  186. pinMode(PIN_STATUS_LED, OUTPUT);
  187. digitalWrite(PIN_STATUS_LED, reason==nullptr?!STATUS_LED_ON:STATUS_LED_ON);
  188. #endif
  189. uint32_t now_ms = millis();
  190. uint32_t location_age_ms = now_ms - t.get_last_location_ms();
  191. uint32_t last_location_age_ms = now_ms - last_location_ms;
  192. if (location_age_ms < last_location_age_ms) {
  193. last_location_ms = t.get_last_location_ms();
  194. }
  195. }
  196. void loop()
  197. {
  198. static uint32_t last_update;
  199. mavlink1.update();
  200. mavlink2.update();
  201. #if AP_DRONECAN_ENABLED
  202. dronecan.update();
  203. #endif
  204. const uint32_t now_ms = millis();
  205. if (now_ms - last_update < 1000/OUTPUT_RATE_HZ) {
  206. // not ready for a new frame yet
  207. return;
  208. }
  209. // the transports have common static data, so we can just use the
  210. // first for status
  211. auto &transport = mavlink1;
  212. bool have_location = false;
  213. const uint32_t last_location_ms = transport.get_last_location_ms();
  214. #if AP_BROADCAST_ON_POWER_UP
  215. // if we are broadcasting on powerup we always mark location valid
  216. // so the location with default data is sent
  217. if (!UAS_data.LocationValid) {
  218. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  219. UAS_data.LocationValid = 1;
  220. }
  221. #else
  222. // only broadcast if we have received a location at least once
  223. if (last_location_ms == 0) {
  224. return;
  225. }
  226. #endif
  227. if (last_location_ms == 0 ||
  228. now_ms - last_location_ms > 5000) {
  229. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  230. }
  231. set_data(transport);
  232. last_update = now_ms;
  233. #if AP_WIFI_NAN_ENABLED
  234. wifi.transmit(UAS_data);
  235. #endif
  236. #if AP_BLE_ENABLED
  237. ble.transmit(UAS_data);
  238. #endif
  239. }