RemoteIDModule.ino 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  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. static ID_OpenDrone squitter;
  15. static MAVLinkSerial mavlink{Serial1, MAVLINK_COMM_0};
  16. static bool squitter_initialised;
  17. #define OUTPUT_RATE_HZ 5
  18. /*
  19. assume ESP32-s3 for now, using pins 17 and 18 for uart
  20. */
  21. #define RX_PIN 17
  22. #define TX_PIN 18
  23. #define DEBUG_BAUDRATE 57600
  24. #define MAVLINK_BAUDRATE 57600
  25. /*
  26. setup serial ports
  27. */
  28. void setup()
  29. {
  30. // Serial for debug printf
  31. Serial.begin(DEBUG_BAUDRATE);
  32. // Serial1 for MAVLink
  33. Serial1.begin(MAVLINK_BAUDRATE, SERIAL_8N1, RX_PIN, TX_PIN);
  34. mavlink.init();
  35. }
  36. static void init_squitter(void)
  37. {
  38. struct UTM_parameters utm_parameters {};
  39. const auto &operator_id = mavlink.get_operator_id();
  40. const auto &basic_id = mavlink.get_basic_id();
  41. const auto &system = mavlink.get_system();
  42. const auto &self_id = mavlink.get_self_id();
  43. strncpy((char*)utm_parameters.UAS_operator, (char *)operator_id.operator_id, sizeof(utm_parameters.UAS_operator));
  44. strncpy((char*)utm_parameters.UAV_id, (char *)basic_id.uas_id, sizeof(utm_parameters.UAV_id));
  45. strncpy((char*)utm_parameters.flight_desc, (char *)self_id.description, sizeof(utm_parameters.flight_desc));
  46. utm_parameters.UA_type = basic_id.ua_type;
  47. utm_parameters.ID_type = basic_id.id_type;
  48. utm_parameters.region = 1; // ??
  49. utm_parameters.EU_category = system.category_eu;
  50. utm_parameters.EU_class = system.class_eu;
  51. // char UTM_id[ID_SIZE * 2] ??
  52. squitter.init(&utm_parameters);
  53. }
  54. void loop()
  55. {
  56. static uint32_t last_update;
  57. mavlink.update();
  58. if (!mavlink.initialised()) {
  59. return;
  60. }
  61. if (!squitter_initialised) {
  62. squitter_initialised = true;
  63. init_squitter();
  64. }
  65. const uint32_t msecs = millis();
  66. if (msecs - last_update < 1000/OUTPUT_RATE_HZ) {
  67. // not ready for a new frame yet
  68. return;
  69. }
  70. last_update = msecs;
  71. const auto &location = mavlink.get_location();
  72. const auto &operator_id = mavlink.get_operator_id();
  73. const auto &system = mavlink.get_system();
  74. struct UTM_data utm_data {};
  75. const float M_PER_SEC_TO_KNOTS = 1.94384449;
  76. utm_data.heading = location.direction * 0.01;
  77. utm_data.latitude_d = location.latitude * 1.0e-7;
  78. utm_data.longitude_d = location.longitude * 1.0e-7;
  79. utm_data.base_latitude = system.operator_latitude * 1.0e-7;
  80. utm_data.base_longitude = system.operator_longitude * 1.0e-7;
  81. utm_data.base_alt_m = system.operator_altitude_geo;
  82. utm_data.alt_msl_m = location.altitude_geodetic;
  83. utm_data.alt_agl_m = location.height;
  84. utm_data.speed_kn = location.speed_horizontal * 0.01 * M_PER_SEC_TO_KNOTS;
  85. utm_data.base_valid = (system.operator_latitude != 0 && system.operator_longitude != 0);
  86. const float groundspeed = location.speed_horizontal * 0.01;
  87. const float vel_N = cos(radians(utm_data.heading)) * groundspeed;
  88. const float vel_E = sin(radians(utm_data.heading)) * groundspeed;
  89. utm_data.vel_N_cm = vel_N * 100;
  90. utm_data.vel_E_cm = vel_E * 100;
  91. utm_data.vel_D_cm = location.speed_vertical * -0.01;
  92. const uint32_t jan_1_2019_s = 1546261200UL;
  93. const time_t unix_s = time_t(system.timestamp) + jan_1_2019_s;
  94. const auto *tm = gmtime(&unix_s);
  95. utm_data.years = tm->tm_year;
  96. utm_data.months = tm->tm_mon;
  97. utm_data.days = tm->tm_mday;
  98. utm_data.hours = tm->tm_hour;
  99. utm_data.minutes = tm->tm_min;
  100. utm_data.seconds = tm->tm_sec;
  101. utm_data.satellites = 8;
  102. //char *hdop_s;
  103. //char *vdop_s;
  104. squitter.transmit(&utm_data);
  105. }