RemoteIDModule.ino 6.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214
  1. /*
  2. implement OpenDroneID MAVLink support, populating squitter for sending bluetooth RemoteID messages
  3. based on example code from https://github.com/sxjack/uav_electronic_ids
  4. */
  5. /*
  6. released under GNU GPL v3 or later
  7. */
  8. #include <Arduino.h>
  9. #include "version.h"
  10. #include <math.h>
  11. #include <time.h>
  12. #include <sys/time.h>
  13. #include <id_open.h>
  14. #include "mavlink.h"
  15. #include "DroneCAN.h"
  16. static ID_OpenDrone squitter;
  17. static DroneCAN dronecan;
  18. static MAVLinkSerial mavlink{Serial1, MAVLINK_COMM_0};
  19. static bool squitter_initialised;
  20. #define OUTPUT_RATE_HZ 5
  21. /*
  22. assume ESP32-s3 for now, using pins 17 and 18 for uart
  23. */
  24. #define RX_PIN 17
  25. #define TX_PIN 18
  26. #define DEBUG_BAUDRATE 57600
  27. #define MAVLINK_BAUDRATE 57600
  28. /*
  29. setup serial ports
  30. */
  31. void setup()
  32. {
  33. // Serial for debug printf
  34. Serial.begin(DEBUG_BAUDRATE);
  35. Serial.printf("ArduRemoteID version %u.%u %08x\n",
  36. FW_VERSION_MAJOR, FW_VERSION_MINOR, GIT_VERSION);
  37. // Serial1 for MAVLink
  38. Serial1.begin(MAVLINK_BAUDRATE, SERIAL_8N1, RX_PIN, TX_PIN);
  39. mavlink.init();
  40. dronecan.init();
  41. }
  42. #define MIN(x,y) ((x)<(y)?(x):(y))
  43. #define ODID_COPY_MAVSTR(to, from) strncpy(to, (const char*)from, MIN(sizeof(to), sizeof(from)))
  44. static void init_squitter_mavlink(void)
  45. {
  46. struct UTM_parameters utm_parameters {};
  47. const auto &operator_id = mavlink.get_operator_id();
  48. const auto &basic_id = mavlink.get_basic_id();
  49. const auto &system = mavlink.get_system();
  50. const auto &self_id = mavlink.get_self_id();
  51. ODID_COPY_MAVSTR(utm_parameters.UAS_operator, operator_id.operator_id);
  52. ODID_COPY_MAVSTR(utm_parameters.UAV_id, basic_id.uas_id);
  53. ODID_COPY_MAVSTR(utm_parameters.flight_desc, self_id.description);
  54. utm_parameters.UA_type = basic_id.ua_type;
  55. utm_parameters.ID_type = basic_id.id_type;
  56. utm_parameters.region = 1; // ??
  57. utm_parameters.EU_category = system.category_eu;
  58. utm_parameters.EU_class = system.class_eu;
  59. // char UTM_id[ID_SIZE * 2] ??
  60. squitter.init(&utm_parameters);
  61. }
  62. #define MIN(x,y) ((x)<(y)?(x):(y))
  63. #define ODID_COPY_STR(to, from) memcpy(to, from.data, MIN(from.len, sizeof(to)))
  64. static void init_squitter_dronecan(void)
  65. {
  66. struct UTM_parameters utm_parameters {};
  67. const auto &operator_id = dronecan.get_operator_id();
  68. const auto &basic_id = dronecan.get_basic_id();
  69. const auto &system = dronecan.get_system();
  70. const auto &self_id = dronecan.get_self_id();
  71. ODID_COPY_STR(utm_parameters.UAS_operator, operator_id.operator_id);
  72. ODID_COPY_STR(utm_parameters.UAV_id, basic_id.uas_id);
  73. ODID_COPY_STR(utm_parameters.flight_desc, self_id.description);
  74. utm_parameters.UA_type = basic_id.ua_type;
  75. utm_parameters.ID_type = basic_id.id_type;
  76. utm_parameters.region = 1; // ??
  77. utm_parameters.EU_category = system.category_eu;
  78. utm_parameters.EU_class = system.class_eu;
  79. squitter.init(&utm_parameters);
  80. }
  81. static void timestamp_to_utm_time(struct UTM_data &utm_data, uint32_t timestamp)
  82. {
  83. const uint32_t jan_1_2019_s = 1546261200UL;
  84. const time_t unix_s = time_t(timestamp) + jan_1_2019_s;
  85. const auto *tm = gmtime(&unix_s);
  86. utm_data.years = tm->tm_year;
  87. utm_data.months = tm->tm_mon;
  88. utm_data.days = tm->tm_mday;
  89. utm_data.hours = tm->tm_hour;
  90. utm_data.minutes = tm->tm_min;
  91. utm_data.seconds = tm->tm_sec;
  92. }
  93. void loop()
  94. {
  95. static uint32_t last_update;
  96. mavlink.update();
  97. dronecan.update();
  98. if (!squitter_initialised && mavlink.system_valid()) {
  99. squitter_initialised = true;
  100. init_squitter_mavlink();
  101. }
  102. if (!squitter_initialised && dronecan.system_valid()) {
  103. squitter_initialised = true;
  104. init_squitter_dronecan();
  105. }
  106. if (!squitter_initialised) {
  107. return;
  108. }
  109. const uint32_t now_ms = millis();
  110. if (now_ms - last_update < 1000/OUTPUT_RATE_HZ) {
  111. // not ready for a new frame yet
  112. return;
  113. }
  114. if (!mavlink.location_valid() &&
  115. !dronecan.location_valid()) {
  116. return;
  117. }
  118. last_update = now_ms;
  119. struct UTM_data utm_data {};
  120. const float M_PER_SEC_TO_KNOTS = 1.94384449;
  121. if (mavlink.location_valid()) {
  122. const auto &location = mavlink.get_location();
  123. //const auto &operator_id = mavlink.get_operator_id();
  124. const auto &system = mavlink.get_system();
  125. utm_data.heading = location.direction * 0.01;
  126. utm_data.latitude_d = location.latitude * 1.0e-7;
  127. utm_data.longitude_d = location.longitude * 1.0e-7;
  128. utm_data.base_latitude = system.operator_latitude * 1.0e-7;
  129. utm_data.base_longitude = system.operator_longitude * 1.0e-7;
  130. utm_data.base_alt_m = system.operator_altitude_geo;
  131. utm_data.alt_msl_m = location.altitude_geodetic;
  132. utm_data.alt_agl_m = location.height;
  133. utm_data.speed_kn = location.speed_horizontal * 0.01 * M_PER_SEC_TO_KNOTS;
  134. utm_data.base_valid = (system.operator_latitude != 0 && system.operator_longitude != 0);
  135. const float groundspeed = location.speed_horizontal * 0.01;
  136. const float vel_N = cos(radians(utm_data.heading)) * groundspeed;
  137. const float vel_E = sin(radians(utm_data.heading)) * groundspeed;
  138. utm_data.vel_N_cm = vel_N * 100;
  139. utm_data.vel_E_cm = vel_E * 100;
  140. utm_data.vel_D_cm = location.speed_vertical * -0.01;
  141. timestamp_to_utm_time(utm_data, system.timestamp);
  142. utm_data.satellites = 8;
  143. }
  144. if (dronecan.location_valid()) {
  145. const auto &location = dronecan.get_location();
  146. //const auto &operator_id = dronecan.get_operator_id();
  147. const auto &system = dronecan.get_system();
  148. utm_data.heading = location.direction * 0.01;
  149. utm_data.latitude_d = location.latitude * 1.0e-7;
  150. utm_data.longitude_d = location.longitude * 1.0e-7;
  151. utm_data.base_latitude = system.operator_latitude * 1.0e-7;
  152. utm_data.base_longitude = system.operator_longitude * 1.0e-7;
  153. utm_data.base_alt_m = system.operator_altitude_geo;
  154. utm_data.alt_msl_m = location.altitude_geodetic;
  155. utm_data.alt_agl_m = location.height;
  156. utm_data.speed_kn = location.speed_horizontal * 0.01 * M_PER_SEC_TO_KNOTS;
  157. utm_data.base_valid = (system.operator_latitude != 0 && system.operator_longitude != 0);
  158. const float groundspeed = location.speed_horizontal * 0.01;
  159. const float vel_N = cos(radians(utm_data.heading)) * groundspeed;
  160. const float vel_E = sin(radians(utm_data.heading)) * groundspeed;
  161. utm_data.vel_N_cm = vel_N * 100;
  162. utm_data.vel_E_cm = vel_E * 100;
  163. utm_data.vel_D_cm = location.speed_vertical * -0.01;
  164. timestamp_to_utm_time(utm_data, system.timestamp);
  165. utm_data.satellites = 8;
  166. }
  167. squitter.transmit(&utm_data);
  168. }