mavlink.cpp 7.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250
  1. /*
  2. mavlink class for handling OpenDroneID messages
  3. */
  4. #include <Arduino.h>
  5. #include "mavlink.h"
  6. #include "board_config.h"
  7. #include "version.h"
  8. #include "parameters.h"
  9. #define SERIAL_BAUD 115200
  10. static HardwareSerial *serial_ports[MAVLINK_COMM_NUM_BUFFERS];
  11. #include <generated/mavlink_helpers.h>
  12. mavlink_system_t mavlink_system = {0, MAV_COMP_ID_ODID_TXRX_1};
  13. /*
  14. send a buffer out a MAVLink channel
  15. */
  16. void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
  17. {
  18. if (chan >= MAVLINK_COMM_NUM_BUFFERS || serial_ports[uint8_t(chan)] == nullptr) {
  19. return;
  20. }
  21. auto &serial = *serial_ports[uint8_t(chan)];
  22. serial.write(buf, len);
  23. }
  24. /*
  25. abstraction for MAVLink on a serial port
  26. */
  27. MAVLinkSerial::MAVLinkSerial(HardwareSerial &_serial, mavlink_channel_t _chan) :
  28. serial(_serial),
  29. chan(_chan)
  30. {
  31. serial_ports[uint8_t(_chan - MAVLINK_COMM_0)] = &serial;
  32. }
  33. void MAVLinkSerial::init(void)
  34. {
  35. // print banner at startup
  36. serial.printf("ArduRemoteID version %u.%u %08x\n",
  37. FW_VERSION_MAJOR, FW_VERSION_MINOR, GIT_VERSION);
  38. }
  39. void MAVLinkSerial::update(void)
  40. {
  41. const uint32_t now_ms = millis();
  42. if (mavlink_system.sysid != 0) {
  43. update_send();
  44. } else if (now_ms - last_hb_warn_ms >= 2000) {
  45. last_hb_warn_ms = millis();
  46. serial.printf("Waiting for heartbeat\n");
  47. }
  48. update_receive();
  49. if (param_request_last_ms != 0 && now_ms - param_request_last_ms > 50) {
  50. param_request_last_ms = now_ms;
  51. float value;
  52. if (param_next->get_as_float(value)) {
  53. mavlink_msg_param_value_send(chan,
  54. param_next->name, value,
  55. MAV_PARAM_TYPE_REAL32,
  56. g.param_count_float(),
  57. g.param_index_float(param_next));
  58. }
  59. param_next++;
  60. if (param_next->ptype == Parameters::ParamType::NONE) {
  61. param_next = nullptr;
  62. param_request_last_ms = 0;
  63. }
  64. }
  65. }
  66. void MAVLinkSerial::update_send(void)
  67. {
  68. uint32_t now_ms = millis();
  69. if (now_ms - last_hb_ms >= 1000) {
  70. last_hb_ms = now_ms;
  71. mavlink_msg_heartbeat_send(
  72. chan,
  73. MAV_TYPE_ODID,
  74. MAV_AUTOPILOT_INVALID,
  75. 0,
  76. 0,
  77. 0);
  78. // send arming status
  79. arm_status_send();
  80. }
  81. }
  82. void MAVLinkSerial::update_receive(void)
  83. {
  84. // receive new packets
  85. mavlink_message_t msg;
  86. mavlink_status_t status;
  87. status.packet_rx_drop_count = 0;
  88. const uint16_t nbytes = serial.available();
  89. for (uint16_t i=0; i<nbytes; i++) {
  90. const uint8_t c = (uint8_t)serial.read();
  91. // Try to get a new message
  92. if (mavlink_parse_char(chan, c, &msg, &status)) {
  93. process_packet(status, msg);
  94. }
  95. }
  96. }
  97. /*
  98. printf via MAVLink STATUSTEXT for debugging
  99. */
  100. void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
  101. {
  102. va_list arg_list;
  103. char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
  104. va_start(arg_list, fmt);
  105. vsnprintf(text, sizeof(text), fmt, arg_list);
  106. va_end(arg_list);
  107. mavlink_msg_statustext_send(chan,
  108. severity,
  109. text,
  110. 0, 0);
  111. }
  112. void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
  113. {
  114. const uint32_t now_ms = millis();
  115. switch (msg.msgid) {
  116. case MAVLINK_MSG_ID_HEARTBEAT: {
  117. mavlink_heartbeat_t hb;
  118. if (mavlink_system.sysid == 0) {
  119. mavlink_msg_heartbeat_decode(&msg, &hb);
  120. if (msg.sysid > 0 && hb.type != MAV_TYPE_GCS) {
  121. mavlink_system.sysid = msg.sysid;
  122. }
  123. }
  124. break;
  125. }
  126. case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
  127. mavlink_msg_open_drone_id_location_decode(&msg, &location);
  128. last_location_ms = now_ms;
  129. break;
  130. }
  131. case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
  132. mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id);
  133. last_basic_id_ms = now_ms;
  134. break;
  135. }
  136. case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
  137. mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
  138. break;
  139. }
  140. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
  141. mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
  142. last_self_id_ms = now_ms;
  143. break;
  144. }
  145. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
  146. mavlink_msg_open_drone_id_system_decode(&msg, &system);
  147. last_system_ms = now_ms;
  148. break;
  149. }
  150. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: {
  151. mavlink_open_drone_id_system_update_t pkt_system_update;
  152. mavlink_msg_open_drone_id_system_update_decode(&msg, &pkt_system_update);
  153. system.operator_latitude = pkt_system_update.operator_latitude;
  154. system.operator_longitude = pkt_system_update.operator_longitude;
  155. system.operator_altitude_geo = pkt_system_update.operator_altitude_geo;
  156. system.timestamp = pkt_system_update.timestamp;
  157. if (last_system_ms != 0) {
  158. // we can only mark system as updated if we have the other
  159. // information already
  160. last_system_ms = now_ms;
  161. }
  162. break;
  163. }
  164. case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
  165. mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
  166. last_operator_id_ms = now_ms;
  167. break;
  168. }
  169. case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
  170. param_next = g.find_by_index_float(0);
  171. param_request_last_ms = millis();
  172. break;
  173. };
  174. case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
  175. mavlink_param_request_read_t pkt;
  176. mavlink_msg_param_request_read_decode(&msg, &pkt);
  177. const Parameters::Param *p;
  178. if (pkt.param_index < 0) {
  179. p = g.find(pkt.param_id);
  180. } else {
  181. p = g.find_by_index_float(pkt.param_index);
  182. }
  183. float value;
  184. if (!p || !p->get_as_float(value)) {
  185. return;
  186. }
  187. mavlink_msg_param_value_send(chan,
  188. p->name, value,
  189. MAV_PARAM_TYPE_REAL32,
  190. g.param_count_float(),
  191. g.param_index_float(p));
  192. break;
  193. }
  194. case MAVLINK_MSG_ID_PARAM_SET: {
  195. mavlink_param_set_t pkt;
  196. mavlink_msg_param_set_decode(&msg, &pkt);
  197. auto *p = g.find(pkt.param_id);
  198. float value;
  199. if (pkt.param_type != MAV_PARAM_TYPE_REAL32 ||
  200. !p || !p->get_as_float(value)) {
  201. return;
  202. }
  203. p->get_as_float(value);
  204. if (g.lock_level != 0 &&
  205. (strcmp(p->name, "LOCK_LEVEL") != 0 ||
  206. uint8_t(pkt.param_value) <= uint8_t(value))) {
  207. // only param set allowed is to increase lock level
  208. mav_printf(MAV_SEVERITY_ERROR, "Parameters locked");
  209. } else {
  210. p->set_as_float(pkt.param_value);
  211. }
  212. p->get_as_float(value);
  213. mavlink_msg_param_value_send(chan,
  214. p->name, value,
  215. MAV_PARAM_TYPE_REAL32,
  216. g.param_count_float(),
  217. g.param_index_float(p));
  218. break;
  219. }
  220. default:
  221. // we don't care about other packets
  222. break;
  223. }
  224. }
  225. void MAVLinkSerial::arm_status_send(void)
  226. {
  227. const uint8_t status = parse_fail==nullptr?MAV_ODID_GOOD_TO_ARM:MAV_ODID_PRE_ARM_FAIL_GENERIC;
  228. const char *reason = parse_fail==nullptr?"":parse_fail;
  229. mavlink_msg_open_drone_id_arm_status_send(
  230. chan,
  231. status,
  232. reason);
  233. }