mavlink.cpp 6.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226
  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. #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. if (mavlink_system.sysid != 0) {
  37. update_send();
  38. }
  39. update_receive();
  40. }
  41. void MAVLinkSerial::update_send(void)
  42. {
  43. uint32_t now_ms = millis();
  44. if (now_ms - last_hb_ms >= 1000) {
  45. last_hb_ms = now_ms;
  46. mavlink_msg_heartbeat_send(
  47. chan,
  48. MAV_TYPE_ODID,
  49. MAV_AUTOPILOT_ARDUPILOTMEGA,
  50. 0,
  51. 0,
  52. 0);
  53. // send arming status
  54. arm_status_send();
  55. }
  56. }
  57. void MAVLinkSerial::update_receive(void)
  58. {
  59. // receive new packets
  60. mavlink_message_t msg;
  61. mavlink_status_t status;
  62. status.packet_rx_drop_count = 0;
  63. const uint16_t nbytes = serial.available();
  64. for (uint16_t i=0; i<nbytes; i++) {
  65. const uint8_t c = (uint8_t)serial.read();
  66. // Try to get a new message
  67. if (mavlink_parse_char(chan, c, &msg, &status)) {
  68. process_packet(status, msg);
  69. }
  70. }
  71. }
  72. /*
  73. printf via MAVLink STATUSTEXT for debugging
  74. */
  75. void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
  76. {
  77. va_list arg_list;
  78. char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
  79. va_start(arg_list, fmt);
  80. vsnprintf(text, sizeof(text), fmt, arg_list);
  81. va_end(arg_list);
  82. mavlink_msg_statustext_send(chan,
  83. severity,
  84. text,
  85. 0, 0);
  86. }
  87. void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
  88. {
  89. const uint32_t now_ms = millis();
  90. switch (msg.msgid) {
  91. case MAVLINK_MSG_ID_HEARTBEAT: {
  92. mavlink_heartbeat_t hb;
  93. if (mavlink_system.sysid == 0) {
  94. mavlink_msg_heartbeat_decode(&msg, &hb);
  95. if (msg.sysid > 0 && hb.type != MAV_TYPE_GCS) {
  96. dev_printf("Got HEARTBEAT from %u/%u\n", msg.sysid, msg.compid);
  97. mavlink_system.sysid = msg.sysid;
  98. }
  99. }
  100. break;
  101. }
  102. case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
  103. dev_printf("Got OPEN_DRONE_ID_LOCATION\n");
  104. mavlink_msg_open_drone_id_location_decode(&msg, &location);
  105. packets_received_mask |= PKT_LOCATION;
  106. last_location_ms = now_ms;
  107. break;
  108. }
  109. case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
  110. dev_printf("Got OPEN_DRONE_ID_BASIC_ID\n");
  111. mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id);
  112. packets_received_mask |= PKT_BASIC_ID;
  113. last_basic_id_ms = now_ms;
  114. break;
  115. }
  116. case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
  117. dev_printf("Got OPEN_DRONE_ID_AUTHENTICATION\n");
  118. mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
  119. packets_received_mask |= PKT_AUTHENTICATION;
  120. break;
  121. }
  122. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
  123. dev_printf("Got OPEN_DRONE_ID_SELF_ID\n");
  124. mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
  125. packets_received_mask |= PKT_SELF_ID;
  126. last_self_id_ms = now_ms;
  127. break;
  128. }
  129. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
  130. dev_printf("Got OPEN_DRONE_ID_SYSTEM\n");
  131. mavlink_msg_open_drone_id_system_decode(&msg, &system);
  132. packets_received_mask |= PKT_SYSTEM;
  133. last_system_ms = now_ms;
  134. break;
  135. }
  136. case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
  137. dev_printf("Got OPEN_DRONE_ID_OPERATOR_ID\n");
  138. mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
  139. packets_received_mask |= PKT_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 {
  170. status = MAV_ODID_GOOD_TO_ARM;
  171. }
  172. mavlink_msg_open_drone_id_arm_status_send(
  173. chan,
  174. status,
  175. reason);
  176. }
  177. /*
  178. return true when we have the base set of packets
  179. */
  180. bool MAVLinkSerial::initialised(void)
  181. {
  182. const uint32_t required = PKT_LOCATION | PKT_BASIC_ID | PKT_SELF_ID | PKT_SYSTEM | PKT_OPERATOR_ID;
  183. return (packets_received_mask & required) == required;
  184. }
  185. bool MAVLinkSerial::system_valid(void)
  186. {
  187. uint32_t now_ms = millis();
  188. uint32_t max_ms = 15000;
  189. if (last_system_ms == 0 ||
  190. last_self_id_ms == 0 ||
  191. last_basic_id_ms == 0 ||
  192. last_operator_id_ms == 0) {
  193. return false;
  194. }
  195. return (now_ms - last_system_ms < max_ms &&
  196. now_ms - last_self_id_ms < max_ms &&
  197. now_ms - last_basic_id_ms < max_ms &&
  198. now_ms - last_operator_id_ms < max_ms);
  199. }
  200. bool MAVLinkSerial::location_valid(void)
  201. {
  202. uint32_t now_ms = millis();
  203. uint32_t max_ms = 2000;
  204. return last_location_ms != 0 && now_ms - last_location_ms < max_ms;
  205. }