RemoteIDModule.ino 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  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. static void init_squitter(void)
  40. {
  41. struct UTM_parameters utm_parameters {};
  42. const auto &operator_id = mavlink.get_operator_id();
  43. const auto &basic_id = mavlink.get_basic_id();
  44. const auto &system = mavlink.get_system();
  45. const auto &self_id = mavlink.get_self_id();
  46. strncpy((char*)utm_parameters.UAS_operator, (char *)operator_id.operator_id, sizeof(utm_parameters.UAS_operator));
  47. strncpy((char*)utm_parameters.UAV_id, (char *)basic_id.uas_id, sizeof(utm_parameters.UAV_id));
  48. strncpy((char*)utm_parameters.flight_desc, (char *)self_id.description, sizeof(utm_parameters.flight_desc));
  49. utm_parameters.UA_type = basic_id.ua_type;
  50. utm_parameters.ID_type = basic_id.id_type;
  51. utm_parameters.region = 1; // ??
  52. utm_parameters.EU_category = system.category_eu;
  53. utm_parameters.EU_class = system.class_eu;
  54. // char UTM_id[ID_SIZE * 2] ??
  55. squitter.init(&utm_parameters);
  56. }
  57. void loop()
  58. {
  59. static uint32_t last_update;
  60. mavlink.update();
  61. dronecan.update();
  62. if (!mavlink.initialised()) {
  63. return;
  64. }
  65. if (!squitter_initialised) {
  66. squitter_initialised = true;
  67. init_squitter();
  68. }
  69. const uint32_t msecs = millis();
  70. if (msecs - last_update < 1000/OUTPUT_RATE_HZ) {
  71. // not ready for a new frame yet
  72. return;
  73. }
  74. last_update = msecs;
  75. const auto &location = mavlink.get_location();
  76. const auto &operator_id = mavlink.get_operator_id();
  77. const auto &system = mavlink.get_system();
  78. struct UTM_data utm_data {};
  79. const float M_PER_SEC_TO_KNOTS = 1.94384449;
  80. utm_data.heading = location.direction * 0.01;
  81. utm_data.latitude_d = location.latitude * 1.0e-7;
  82. utm_data.longitude_d = location.longitude * 1.0e-7;
  83. utm_data.base_latitude = system.operator_latitude * 1.0e-7;
  84. utm_data.base_longitude = system.operator_longitude * 1.0e-7;
  85. utm_data.base_alt_m = system.operator_altitude_geo;
  86. utm_data.alt_msl_m = location.altitude_geodetic;
  87. utm_data.alt_agl_m = location.height;
  88. utm_data.speed_kn = location.speed_horizontal * 0.01 * M_PER_SEC_TO_KNOTS;
  89. utm_data.base_valid = (system.operator_latitude != 0 && system.operator_longitude != 0);
  90. const float groundspeed = location.speed_horizontal * 0.01;
  91. const float vel_N = cos(radians(utm_data.heading)) * groundspeed;
  92. const float vel_E = sin(radians(utm_data.heading)) * groundspeed;
  93. utm_data.vel_N_cm = vel_N * 100;
  94. utm_data.vel_E_cm = vel_E * 100;
  95. utm_data.vel_D_cm = location.speed_vertical * -0.01;
  96. const uint32_t jan_1_2019_s = 1546261200UL;
  97. const time_t unix_s = time_t(system.timestamp) + jan_1_2019_s;
  98. const auto *tm = gmtime(&unix_s);
  99. utm_data.years = tm->tm_year;
  100. utm_data.months = tm->tm_mon;
  101. utm_data.days = tm->tm_mday;
  102. utm_data.hours = tm->tm_hour;
  103. utm_data.minutes = tm->tm_min;
  104. utm_data.seconds = tm->tm_sec;
  105. utm_data.satellites = 8;
  106. //char *hdop_s;
  107. //char *vdop_s;
  108. squitter.transmit(&utm_data);
  109. }