mavlink.cpp 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181
  1. /*
  2. mavlink class for handling OpenDroneID messages
  3. */
  4. #include <Arduino.h>
  5. #include "mavlink.h"
  6. #define SERIAL_BAUD 115200
  7. static HardwareSerial *serial_ports[MAVLINK_COMM_NUM_BUFFERS];
  8. #include <generated/mavlink_helpers.h>
  9. mavlink_system_t mavlink_system = {2,1};
  10. #define dev_printf(fmt, args ...) do {Serial.printf(fmt, ## args); } while(0)
  11. /*
  12. send a buffer out a MAVLink channel
  13. */
  14. void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
  15. {
  16. if (chan >= MAVLINK_COMM_NUM_BUFFERS || serial_ports[uint8_t(chan)] == nullptr) {
  17. return;
  18. }
  19. auto &serial = *serial_ports[uint8_t(chan)];
  20. serial.write(buf, len);
  21. }
  22. /*
  23. abstraction for MAVLink on a serial port
  24. */
  25. MAVLinkSerial::MAVLinkSerial(HardwareSerial &_serial, mavlink_channel_t _chan) :
  26. serial(_serial),
  27. chan(_chan)
  28. {
  29. serial_ports[uint8_t(_chan - MAVLINK_COMM_0)] = &serial;
  30. }
  31. void MAVLinkSerial::init(void)
  32. {
  33. }
  34. void MAVLinkSerial::update(void)
  35. {
  36. update_send();
  37. update_receive();
  38. }
  39. void MAVLinkSerial::update_send(void)
  40. {
  41. uint32_t now_ms = millis();
  42. if (now_ms - last_hb_ms >= 1000) {
  43. last_hb_ms = now_ms;
  44. mavlink_msg_heartbeat_send(
  45. chan,
  46. MAV_TYPE_ODID,
  47. MAV_AUTOPILOT_ARDUPILOTMEGA,
  48. 0,
  49. 0,
  50. 0);
  51. }
  52. }
  53. void MAVLinkSerial::update_receive(void)
  54. {
  55. // receive new packets
  56. mavlink_message_t msg;
  57. mavlink_status_t status;
  58. uint32_t now_ms = millis();
  59. status.packet_rx_drop_count = 0;
  60. const uint16_t nbytes = serial.available();
  61. for (uint16_t i=0; i<nbytes; i++) {
  62. const uint8_t c = (uint8_t)serial.read();
  63. // Try to get a new message
  64. if (mavlink_parse_char(chan, c, &msg, &status)) {
  65. process_packet(status, msg);
  66. }
  67. }
  68. }
  69. /*
  70. printf via MAVLink STATUSTEXT for debugging
  71. */
  72. void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
  73. {
  74. va_list arg_list;
  75. char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
  76. va_start(arg_list, fmt);
  77. vsnprintf(text, sizeof(text), fmt, arg_list);
  78. va_end(arg_list);
  79. mavlink_msg_statustext_send(chan,
  80. severity,
  81. text,
  82. 0, 0);
  83. }
  84. void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
  85. {
  86. const uint32_t now_ms = millis();
  87. switch (msg.msgid) {
  88. case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
  89. dev_printf("Got OPEN_DRONE_ID_LOCATION\n");
  90. mavlink_msg_open_drone_id_location_decode(&msg, &location);
  91. packets_received_mask |= PKT_LOCATION;
  92. last_location_ms = now_ms;
  93. break;
  94. }
  95. case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
  96. dev_printf("Got OPEN_DRONE_ID_BASIC_ID\n");
  97. mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id);
  98. packets_received_mask |= PKT_BASIC_ID;
  99. last_basic_id_ms = now_ms;
  100. break;
  101. }
  102. case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
  103. dev_printf("Got OPEN_DRONE_ID_AUTHENTICATION\n");
  104. mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
  105. packets_received_mask |= PKT_AUTHENTICATION;
  106. break;
  107. }
  108. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
  109. dev_printf("Got OPEN_DRONE_ID_SELF_ID\n");
  110. mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
  111. packets_received_mask |= PKT_SELF_ID;
  112. last_self_id_ms = now_ms;
  113. break;
  114. }
  115. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
  116. dev_printf("Got OPEN_DRONE_ID_SYSTEM\n");
  117. mavlink_msg_open_drone_id_system_decode(&msg, &system);
  118. packets_received_mask |= PKT_SYSTEM;
  119. last_system_msg_ms = now_ms;
  120. break;
  121. }
  122. case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
  123. dev_printf("Got OPEN_DRONE_ID_OPERATOR_ID\n");
  124. mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
  125. packets_received_mask |= PKT_OPERATOR_ID;
  126. last_operator_id_ms = now_ms;
  127. break;
  128. }
  129. default:
  130. // we don't care about other packets
  131. break;
  132. }
  133. }
  134. /*
  135. return true when we have the base set of packets
  136. */
  137. bool MAVLinkSerial::initialised(void)
  138. {
  139. const uint32_t required = PKT_LOCATION | PKT_BASIC_ID | PKT_SELF_ID | PKT_SYSTEM | PKT_OPERATOR_ID;
  140. return (packets_received_mask & required) == required;
  141. }
  142. bool MAVLinkSerial::system_valid(void)
  143. {
  144. uint32_t now_ms = millis();
  145. uint32_t max_ms = 15000;
  146. if (last_system_ms == 0 ||
  147. last_self_id_ms == 0 ||
  148. last_basic_id_ms == 0 ||
  149. last_system_ms == 0 ||
  150. last_operator_id_ms == 0) {
  151. return false;
  152. }
  153. return (now_ms - last_system_ms < max_ms &&
  154. now_ms - last_self_id_ms < max_ms &&
  155. now_ms - last_basic_id_ms < max_ms &&
  156. now_ms - last_operator_id_ms < max_ms);
  157. }
  158. bool MAVLinkSerial::location_valid(void)
  159. {
  160. uint32_t now_ms = millis();
  161. uint32_t max_ms = 2000;
  162. return last_location_ms != 0 && now_ms - last_location_ms < max_ms;
  163. }