RemoteIDModule.ino 6.8 KB

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