mavlink.cpp 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213
  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. // send arming status
  52. arm_status_send();
  53. }
  54. }
  55. void MAVLinkSerial::update_receive(void)
  56. {
  57. // receive new packets
  58. mavlink_message_t msg;
  59. mavlink_status_t status;
  60. status.packet_rx_drop_count = 0;
  61. const uint16_t nbytes = serial.available();
  62. for (uint16_t i=0; i<nbytes; i++) {
  63. const uint8_t c = (uint8_t)serial.read();
  64. // Try to get a new message
  65. if (mavlink_parse_char(chan, c, &msg, &status)) {
  66. process_packet(status, msg);
  67. }
  68. }
  69. }
  70. /*
  71. printf via MAVLink STATUSTEXT for debugging
  72. */
  73. void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
  74. {
  75. va_list arg_list;
  76. char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
  77. va_start(arg_list, fmt);
  78. vsnprintf(text, sizeof(text), fmt, arg_list);
  79. va_end(arg_list);
  80. mavlink_msg_statustext_send(chan,
  81. severity,
  82. text,
  83. 0, 0);
  84. }
  85. void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
  86. {
  87. const uint32_t now_ms = millis();
  88. switch (msg.msgid) {
  89. case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
  90. dev_printf("Got OPEN_DRONE_ID_LOCATION\n");
  91. mavlink_msg_open_drone_id_location_decode(&msg, &location);
  92. packets_received_mask |= PKT_LOCATION;
  93. last_location_ms = now_ms;
  94. break;
  95. }
  96. case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
  97. dev_printf("Got OPEN_DRONE_ID_BASIC_ID\n");
  98. mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id);
  99. packets_received_mask |= PKT_BASIC_ID;
  100. last_basic_id_ms = now_ms;
  101. break;
  102. }
  103. case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
  104. dev_printf("Got OPEN_DRONE_ID_AUTHENTICATION\n");
  105. mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
  106. packets_received_mask |= PKT_AUTHENTICATION;
  107. break;
  108. }
  109. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
  110. dev_printf("Got OPEN_DRONE_ID_SELF_ID\n");
  111. mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
  112. packets_received_mask |= PKT_SELF_ID;
  113. last_self_id_ms = now_ms;
  114. break;
  115. }
  116. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
  117. dev_printf("Got OPEN_DRONE_ID_SYSTEM\n");
  118. mavlink_msg_open_drone_id_system_decode(&msg, &system);
  119. packets_received_mask |= PKT_SYSTEM;
  120. last_system_ms = now_ms;
  121. break;
  122. }
  123. case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
  124. dev_printf("Got OPEN_DRONE_ID_OPERATOR_ID\n");
  125. mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
  126. packets_received_mask |= PKT_OPERATOR_ID;
  127. last_operator_id_ms = now_ms;
  128. break;
  129. }
  130. default:
  131. // we don't care about other packets
  132. break;
  133. }
  134. }
  135. void MAVLinkSerial::arm_status_send(void)
  136. {
  137. const uint32_t max_age_location_ms = 3000;
  138. const uint32_t max_age_other_ms = 22000;
  139. const uint32_t now_ms = millis();
  140. const char *reason = "";
  141. uint8_t status = MAV_ODID_PRE_ARM_FAIL_GENERIC;
  142. if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
  143. reason = "missing location message";
  144. } else if (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms) {
  145. reason = "missing basic_id message";
  146. } else if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
  147. reason = "missing self_id message";
  148. } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
  149. reason = "missing operator_id message";
  150. } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) {
  151. reason = "missing system message";
  152. } else if (location.latitude == 0 && location.longitude == 0) {
  153. reason = "Bad location";
  154. } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
  155. reason = "Bad operator location";
  156. } else {
  157. status = MAV_ODID_GOOD_TO_ARM;
  158. }
  159. mavlink_msg_open_drone_id_arm_status_send(
  160. chan,
  161. status,
  162. reason);
  163. }
  164. /*
  165. return true when we have the base set of packets
  166. */
  167. bool MAVLinkSerial::initialised(void)
  168. {
  169. const uint32_t required = PKT_LOCATION | PKT_BASIC_ID | PKT_SELF_ID | PKT_SYSTEM | PKT_OPERATOR_ID;
  170. return (packets_received_mask & required) == required;
  171. }
  172. bool MAVLinkSerial::system_valid(void)
  173. {
  174. uint32_t now_ms = millis();
  175. uint32_t max_ms = 15000;
  176. if (last_system_ms == 0 ||
  177. last_self_id_ms == 0 ||
  178. last_basic_id_ms == 0 ||
  179. last_operator_id_ms == 0) {
  180. return false;
  181. }
  182. return (now_ms - last_system_ms < max_ms &&
  183. now_ms - last_self_id_ms < max_ms &&
  184. now_ms - last_basic_id_ms < max_ms &&
  185. now_ms - last_operator_id_ms < max_ms);
  186. }
  187. bool MAVLinkSerial::location_valid(void)
  188. {
  189. uint32_t now_ms = millis();
  190. uint32_t max_ms = 2000;
  191. return last_location_ms != 0 && now_ms - last_location_ms < max_ms;
  192. }