RemoteIDModule.ino 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341
  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. }
  65. #define IMIN(x,y) ((x)<(y)?(x):(y))
  66. #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
  67. /*
  68. check parsing of UAS_data, this checks ranges of values to ensure we
  69. will produce a valid pack
  70. */
  71. static const char *check_parse(void)
  72. {
  73. {
  74. ODID_Location_encoded encoded {};
  75. if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
  76. return "bad LOCATION data";
  77. }
  78. }
  79. {
  80. ODID_System_encoded encoded {};
  81. if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
  82. return "bad SYSTEM data";
  83. }
  84. }
  85. {
  86. ODID_BasicID_encoded encoded {};
  87. if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
  88. return "bad BASIC_ID data";
  89. }
  90. }
  91. {
  92. ODID_SelfID_encoded encoded {};
  93. if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
  94. return "bad SELF_ID data";
  95. }
  96. }
  97. {
  98. ODID_OperatorID_encoded encoded {};
  99. if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
  100. return "bad OPERATOR_ID data";
  101. }
  102. }
  103. return nullptr;
  104. }
  105. static void set_data_mavlink(MAVLinkSerial &m)
  106. {
  107. const auto &operator_id = m.get_operator_id();
  108. const auto &basic_id = m.get_basic_id();
  109. const auto &system = m.get_system();
  110. const auto &self_id = m.get_self_id();
  111. const auto &location = m.get_location();
  112. // BasicID
  113. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  114. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  115. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  116. UAS_data.BasicIDValid[0] = 1;
  117. // OperatorID
  118. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  119. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  120. UAS_data.OperatorIDValid = 1;
  121. // SelfID
  122. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  123. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  124. UAS_data.SelfIDValid = 1;
  125. // System
  126. if (system.timestamp != 0) {
  127. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  128. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  129. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  130. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  131. UAS_data.System.AreaCount = system.area_count;
  132. UAS_data.System.AreaRadius = system.area_radius;
  133. UAS_data.System.AreaCeiling = system.area_ceiling;
  134. UAS_data.System.AreaFloor = system.area_floor;
  135. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  136. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  137. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  138. UAS_data.System.Timestamp = system.timestamp;
  139. UAS_data.SystemValid = 1;
  140. }
  141. // Location
  142. if (location.timestamp != 0) {
  143. UAS_data.Location.Status = (ODID_status_t)location.status;
  144. UAS_data.Location.Direction = location.direction*0.01;
  145. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  146. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  147. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  148. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  149. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  150. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  151. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  152. UAS_data.Location.Height = location.height;
  153. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  154. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  155. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  156. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  157. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  158. UAS_data.Location.TimeStamp = location.timestamp;
  159. UAS_data.LocationValid = 1;
  160. }
  161. m.set_parse_fail(check_parse());
  162. uint32_t now_ms = millis();
  163. uint32_t location_age_ms = now_ms - m.get_last_location_ms();
  164. uint32_t last_location_age_ms = now_ms - last_location_ms;
  165. if (location_age_ms < last_location_age_ms) {
  166. last_location_ms = m.get_last_location_ms();
  167. }
  168. }
  169. #undef ODID_COPY_STR
  170. #define ODID_COPY_STR(to, from) memcpy(to, from.data, IMIN(from.len, sizeof(to)))
  171. #if AP_DRONECAN_ENABLED
  172. static void set_data_dronecan(void)
  173. {
  174. const auto &operator_id = dronecan.get_operator_id();
  175. const auto &basic_id = dronecan.get_basic_id();
  176. const auto &system = dronecan.get_system();
  177. const auto &self_id = dronecan.get_self_id();
  178. const auto &location = dronecan.get_location();
  179. // BasicID
  180. UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
  181. UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
  182. ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
  183. UAS_data.BasicIDValid[0] = 1;
  184. // OperatorID
  185. UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
  186. ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
  187. UAS_data.OperatorIDValid = 1;
  188. // SelfID
  189. UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
  190. ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
  191. UAS_data.SelfIDValid = 1;
  192. // System
  193. if (system.timestamp != 0) {
  194. UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
  195. UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
  196. UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
  197. UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
  198. UAS_data.System.AreaCount = system.area_count;
  199. UAS_data.System.AreaRadius = system.area_radius;
  200. UAS_data.System.AreaCeiling = system.area_ceiling;
  201. UAS_data.System.AreaFloor = system.area_floor;
  202. UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
  203. UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
  204. UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
  205. UAS_data.System.Timestamp = system.timestamp;
  206. UAS_data.SystemValid = 1;
  207. }
  208. // Location
  209. if (location.timestamp != 0) {
  210. UAS_data.Location.Status = (ODID_status_t)location.status;
  211. UAS_data.Location.Direction = location.direction*0.01;
  212. UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
  213. UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
  214. UAS_data.Location.Latitude = location.latitude*1.0e-7;
  215. UAS_data.Location.Longitude = location.longitude*1.0e-7;
  216. UAS_data.Location.AltitudeBaro = location.altitude_barometric;
  217. UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
  218. UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
  219. UAS_data.Location.Height = location.height;
  220. UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
  221. UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
  222. UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
  223. UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
  224. UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
  225. UAS_data.Location.TimeStamp = location.timestamp;
  226. UAS_data.LocationValid = 1;
  227. }
  228. dronecan.set_parse_fail(check_parse());
  229. uint32_t now_ms = millis();
  230. uint32_t location_age_ms = now_ms - dronecan.get_last_location_ms();
  231. uint32_t last_location_age_ms = now_ms - last_location_ms;
  232. if (location_age_ms < last_location_age_ms) {
  233. last_location_ms = dronecan.get_last_location_ms();
  234. }
  235. }
  236. #endif // AP_DRONECAN_ENABLED
  237. void loop()
  238. {
  239. static uint32_t last_update;
  240. mavlink1.update();
  241. mavlink2.update();
  242. #if AP_DRONECAN_ENABLED
  243. dronecan.update();
  244. #endif
  245. const uint32_t now_ms = millis();
  246. if (now_ms - last_update < 1000/OUTPUT_RATE_HZ) {
  247. // not ready for a new frame yet
  248. return;
  249. }
  250. bool have_location = false;
  251. #if AP_MAVLINK_ENABLED
  252. const bool mavlink1_ok = mavlink1.get_last_location_ms() != 0;
  253. const bool mavlink2_ok = mavlink2.get_last_location_ms() != 0;
  254. have_location |= mavlink1_ok || mavlink2_ok;
  255. #endif
  256. #if AP_DRONECAN_ENABLED
  257. const bool dronecan_ok = dronecan.get_last_location_ms() != 0;
  258. have_location |= dronecan_ok;
  259. #endif
  260. #if AP_BROADCAST_ON_POWER_UP
  261. // if we are broadcasting on powerup we always mark location valid
  262. // so the location with default data is sent
  263. if (!UAS_data.LocationValid) {
  264. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  265. UAS_data.LocationValid = 1;
  266. }
  267. #else
  268. // only broadcast if we have received a location at least once
  269. if (!have_location) {
  270. return;
  271. }
  272. #endif
  273. if (now_ms - last_location_ms > 5000) {
  274. UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
  275. }
  276. #if AP_MAVLINK_ENABLED
  277. if (mavlink1_ok) {
  278. set_data_mavlink(mavlink1);
  279. }
  280. if (mavlink2_ok) {
  281. set_data_mavlink(mavlink2);
  282. }
  283. #endif
  284. #if AP_DRONECAN_ENABLED
  285. if (dronecan_ok) {
  286. set_data_dronecan();
  287. }
  288. #endif
  289. last_update = now_ms;
  290. #if AP_WIFI_NAN_ENABLED
  291. wifi.transmit(UAS_data);
  292. #endif
  293. #if AP_BLE_ENABLED
  294. ble.transmit(UAS_data);
  295. #endif
  296. }