mavlink.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195
  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 = {0,MAV_COMP_ID_ODID_TXRX_1};
  10. /*
  11. send a buffer out a MAVLink channel
  12. */
  13. void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
  14. {
  15. if (chan >= MAVLINK_COMM_NUM_BUFFERS || serial_ports[uint8_t(chan)] == nullptr) {
  16. return;
  17. }
  18. auto &serial = *serial_ports[uint8_t(chan)];
  19. serial.write(buf, len);
  20. }
  21. /*
  22. abstraction for MAVLink on a serial port
  23. */
  24. MAVLinkSerial::MAVLinkSerial(HardwareSerial &_serial, mavlink_channel_t _chan) :
  25. serial(_serial),
  26. chan(_chan)
  27. {
  28. serial_ports[uint8_t(_chan - MAVLINK_COMM_0)] = &serial;
  29. }
  30. void MAVLinkSerial::init(void)
  31. {
  32. }
  33. void MAVLinkSerial::update(void)
  34. {
  35. if (mavlink_system.sysid != 0) {
  36. update_send();
  37. }
  38. update_receive();
  39. }
  40. void MAVLinkSerial::update_send(void)
  41. {
  42. uint32_t now_ms = millis();
  43. if (now_ms - last_hb_ms >= 1000) {
  44. last_hb_ms = now_ms;
  45. mavlink_msg_heartbeat_send(
  46. chan,
  47. MAV_TYPE_ODID,
  48. MAV_AUTOPILOT_ARDUPILOTMEGA,
  49. 0,
  50. 0,
  51. 0);
  52. // send arming status
  53. arm_status_send();
  54. }
  55. }
  56. void MAVLinkSerial::update_receive(void)
  57. {
  58. // receive new packets
  59. mavlink_message_t msg;
  60. mavlink_status_t status;
  61. status.packet_rx_drop_count = 0;
  62. const uint16_t nbytes = serial.available();
  63. for (uint16_t i=0; i<nbytes; i++) {
  64. const uint8_t c = (uint8_t)serial.read();
  65. // Try to get a new message
  66. if (mavlink_parse_char(chan, c, &msg, &status)) {
  67. process_packet(status, msg);
  68. }
  69. }
  70. }
  71. /*
  72. printf via MAVLink STATUSTEXT for debugging
  73. */
  74. void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
  75. {
  76. va_list arg_list;
  77. char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
  78. va_start(arg_list, fmt);
  79. vsnprintf(text, sizeof(text), fmt, arg_list);
  80. va_end(arg_list);
  81. mavlink_msg_statustext_send(chan,
  82. severity,
  83. text,
  84. 0, 0);
  85. }
  86. void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
  87. {
  88. const uint32_t now_ms = millis();
  89. switch (msg.msgid) {
  90. case MAVLINK_MSG_ID_HEARTBEAT: {
  91. mavlink_heartbeat_t hb;
  92. if (mavlink_system.sysid == 0) {
  93. mavlink_msg_heartbeat_decode(&msg, &hb);
  94. if (msg.sysid > 0 && hb.type != MAV_TYPE_GCS) {
  95. mavlink_system.sysid = msg.sysid;
  96. }
  97. }
  98. break;
  99. }
  100. case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
  101. mavlink_msg_open_drone_id_location_decode(&msg, &location);
  102. last_location_ms = now_ms;
  103. break;
  104. }
  105. case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
  106. mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id);
  107. last_basic_id_ms = now_ms;
  108. break;
  109. }
  110. case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
  111. mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
  112. break;
  113. }
  114. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
  115. mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
  116. last_self_id_ms = now_ms;
  117. break;
  118. }
  119. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
  120. mavlink_msg_open_drone_id_system_decode(&msg, &system);
  121. last_system_ms = now_ms;
  122. break;
  123. }
  124. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: {
  125. mavlink_open_drone_id_system_update_t pkt_system_update;
  126. mavlink_msg_open_drone_id_system_update_decode(&msg, &pkt_system_update);
  127. system.operator_latitude = pkt_system_update.operator_latitude;
  128. system.operator_longitude = pkt_system_update.operator_longitude;
  129. system.operator_altitude_geo = pkt_system_update.operator_altitude_geo;
  130. system.timestamp = pkt_system_update.timestamp;
  131. if (last_system_ms != 0) {
  132. // we can only mark system as updated if we have the other
  133. // information already
  134. last_system_ms = now_ms;
  135. }
  136. break;
  137. }
  138. case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
  139. mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
  140. last_operator_id_ms = now_ms;
  141. break;
  142. }
  143. default:
  144. // we don't care about other packets
  145. break;
  146. }
  147. }
  148. void MAVLinkSerial::arm_status_send(void)
  149. {
  150. const uint32_t max_age_location_ms = 3000;
  151. const uint32_t max_age_other_ms = 22000;
  152. const uint32_t now_ms = millis();
  153. const char *reason = "";
  154. uint8_t status = MAV_ODID_PRE_ARM_FAIL_GENERIC;
  155. if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
  156. reason = "missing location message";
  157. } else if (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms) {
  158. reason = "missing basic_id message";
  159. } else if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
  160. reason = "missing self_id message";
  161. } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
  162. reason = "missing operator_id message";
  163. } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) {
  164. reason = "missing system message";
  165. } else if (location.latitude == 0 && location.longitude == 0) {
  166. reason = "Bad location";
  167. } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
  168. reason = "Bad operator location";
  169. } else if (parse_fail != nullptr) {
  170. reason = parse_fail;
  171. } else {
  172. status = MAV_ODID_GOOD_TO_ARM;
  173. }
  174. mavlink_msg_open_drone_id_arm_status_send(
  175. chan,
  176. status,
  177. reason);
  178. }