mavlink.cpp 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172
  1. /*
  2. mavlink class for handling OpenDroneID messages
  3. */
  4. #include <Arduino.h>
  5. #include "mavlink.h"
  6. #include "board_config.h"
  7. #define SERIAL_BAUD 115200
  8. static HardwareSerial *serial_ports[MAVLINK_COMM_NUM_BUFFERS];
  9. #include <generated/mavlink_helpers.h>
  10. mavlink_system_t mavlink_system = {0,MAV_COMP_ID_ODID_TXRX_1};
  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. mavlink_system.sysid = msg.sysid;
  97. }
  98. }
  99. break;
  100. }
  101. case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
  102. mavlink_msg_open_drone_id_location_decode(&msg, &location);
  103. last_location_ms = now_ms;
  104. break;
  105. }
  106. case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
  107. mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id);
  108. last_basic_id_ms = now_ms;
  109. break;
  110. }
  111. case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
  112. mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
  113. break;
  114. }
  115. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
  116. mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
  117. last_self_id_ms = now_ms;
  118. break;
  119. }
  120. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
  121. mavlink_msg_open_drone_id_system_decode(&msg, &system);
  122. last_system_ms = now_ms;
  123. break;
  124. }
  125. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: {
  126. mavlink_open_drone_id_system_update_t pkt_system_update;
  127. mavlink_msg_open_drone_id_system_update_decode(&msg, &pkt_system_update);
  128. system.operator_latitude = pkt_system_update.operator_latitude;
  129. system.operator_longitude = pkt_system_update.operator_longitude;
  130. system.operator_altitude_geo = pkt_system_update.operator_altitude_geo;
  131. system.timestamp = pkt_system_update.timestamp;
  132. if (last_system_ms != 0) {
  133. // we can only mark system as updated if we have the other
  134. // information already
  135. last_system_ms = now_ms;
  136. }
  137. break;
  138. }
  139. case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
  140. mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
  141. last_operator_id_ms = now_ms;
  142. break;
  143. }
  144. default:
  145. // we don't care about other packets
  146. break;
  147. }
  148. }
  149. void MAVLinkSerial::arm_status_send(void)
  150. {
  151. const uint8_t status = parse_fail==nullptr?MAV_ODID_GOOD_TO_ARM:MAV_ODID_PRE_ARM_FAIL_GENERIC;
  152. const char *reason = parse_fail==nullptr?"":parse_fail;
  153. mavlink_msg_open_drone_id_arm_status_send(
  154. chan,
  155. status,
  156. reason);
  157. }