mavlink.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303
  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. mavlink_system.sysid = g.mavlink_sysid;
  39. }
  40. void MAVLinkSerial::update(void)
  41. {
  42. const uint32_t now_ms = millis();
  43. if (mavlink_system.sysid != 0) {
  44. update_send();
  45. } else if (g.mavlink_sysid != 0) {
  46. mavlink_system.sysid = g.mavlink_sysid;
  47. } else if (now_ms - last_hb_warn_ms >= 2000) {
  48. last_hb_warn_ms = millis();
  49. serial.printf("Waiting for heartbeat\n");
  50. }
  51. update_receive();
  52. if (param_request_last_ms != 0 && now_ms - param_request_last_ms > 50) {
  53. param_request_last_ms = now_ms;
  54. float value;
  55. if (param_next->get_as_float(value)) {
  56. mavlink_msg_param_value_send(chan,
  57. param_next->name, value,
  58. MAV_PARAM_TYPE_REAL32,
  59. g.param_count_float(),
  60. g.param_index_float(param_next));
  61. }
  62. param_next++;
  63. if (param_next->ptype == Parameters::ParamType::NONE) {
  64. param_next = nullptr;
  65. param_request_last_ms = 0;
  66. }
  67. }
  68. }
  69. void MAVLinkSerial::update_send(void)
  70. {
  71. uint32_t now_ms = millis();
  72. if (now_ms - last_hb_ms >= 1000) {
  73. last_hb_ms = now_ms;
  74. mavlink_msg_heartbeat_send(
  75. chan,
  76. MAV_TYPE_ODID,
  77. MAV_AUTOPILOT_INVALID,
  78. 0,
  79. 0,
  80. 0);
  81. // send arming status
  82. arm_status_send();
  83. }
  84. }
  85. void MAVLinkSerial::update_receive(void)
  86. {
  87. // receive new packets
  88. mavlink_message_t msg;
  89. mavlink_status_t status;
  90. status.packet_rx_drop_count = 0;
  91. const uint16_t nbytes = serial.available();
  92. for (uint16_t i=0; i<nbytes; i++) {
  93. const uint8_t c = (uint8_t)serial.read();
  94. // Try to get a new message
  95. if (mavlink_parse_char(chan, c, &msg, &status)) {
  96. process_packet(status, msg);
  97. }
  98. }
  99. }
  100. /*
  101. printf via MAVLink STATUSTEXT for debugging
  102. */
  103. void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
  104. {
  105. va_list arg_list;
  106. char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
  107. va_start(arg_list, fmt);
  108. vsnprintf(text, sizeof(text), fmt, arg_list);
  109. va_end(arg_list);
  110. mavlink_msg_statustext_send(chan,
  111. severity,
  112. text,
  113. 0, 0);
  114. }
  115. void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
  116. {
  117. const uint32_t now_ms = millis();
  118. switch (msg.msgid) {
  119. case MAVLINK_MSG_ID_HEARTBEAT: {
  120. mavlink_heartbeat_t hb;
  121. if (mavlink_system.sysid == 0) {
  122. mavlink_msg_heartbeat_decode(&msg, &hb);
  123. if (msg.sysid > 0 && hb.type != MAV_TYPE_GCS) {
  124. mavlink_system.sysid = msg.sysid;
  125. }
  126. }
  127. break;
  128. }
  129. case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
  130. mavlink_msg_open_drone_id_location_decode(&msg, &location);
  131. if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
  132. Serial.printf("MAVLink: got Location\n");
  133. }
  134. if (last_location_timestamp != location.timestamp) {
  135. //only update the timestamp if we receive information with a different timestamp
  136. last_location_ms = millis();
  137. last_location_timestamp = location.timestamp;
  138. }
  139. last_location_ms = now_ms;
  140. break;
  141. }
  142. case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
  143. mavlink_open_drone_id_basic_id_t basic_id_tmp;
  144. if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
  145. Serial.printf("MAVLink: got BasicID\n");
  146. }
  147. mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id_tmp);
  148. if ((strlen((const char*) basic_id_tmp.uas_id) > 0) && (basic_id_tmp.id_type > 0) && (basic_id_tmp.id_type <= MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID)) {
  149. //only update if we receive valid data
  150. basic_id = basic_id_tmp;
  151. last_basic_id_ms = now_ms;
  152. }
  153. break;
  154. }
  155. case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
  156. mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
  157. if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
  158. Serial.printf("MAVLink: got Auth\n");
  159. }
  160. break;
  161. }
  162. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
  163. mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
  164. if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
  165. Serial.printf("MAVLink: got SelfID\n");
  166. }
  167. last_self_id_ms = now_ms;
  168. break;
  169. }
  170. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
  171. mavlink_msg_open_drone_id_system_decode(&msg, &system);
  172. if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
  173. Serial.printf("MAVLink: got System\n");
  174. }
  175. if ((last_system_timestamp != system.timestamp) || (system.timestamp == 0)) {
  176. //only update the timestamp if we receive information with a different timestamp
  177. last_system_ms = millis();
  178. last_system_timestamp = system.timestamp;
  179. }
  180. break;
  181. }
  182. case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: {
  183. if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
  184. Serial.printf("MAVLink: got System update\n");
  185. }
  186. mavlink_open_drone_id_system_update_t pkt_system_update;
  187. mavlink_msg_open_drone_id_system_update_decode(&msg, &pkt_system_update);
  188. system.operator_latitude = pkt_system_update.operator_latitude;
  189. system.operator_longitude = pkt_system_update.operator_longitude;
  190. system.operator_altitude_geo = pkt_system_update.operator_altitude_geo;
  191. system.timestamp = pkt_system_update.timestamp;
  192. if (last_system_ms != 0) {
  193. // we can only mark system as updated if we have the other
  194. // information already
  195. if ((last_system_timestamp != system.timestamp) || (pkt_system_update.timestamp == 0)) {
  196. //only update the timestamp if we receive information with a different timestamp
  197. last_system_ms = millis();
  198. last_system_timestamp = pkt_system_update.timestamp;
  199. }
  200. last_system_ms = now_ms;
  201. }
  202. break;
  203. }
  204. case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
  205. mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
  206. if (g.options & OPTIONS_PRINT_RID_MAVLINK) {
  207. Serial.printf("MAVLink: got OperatorID\n");
  208. }
  209. last_operator_id_ms = now_ms;
  210. break;
  211. }
  212. case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
  213. param_next = g.find_by_index_float(0);
  214. param_request_last_ms = millis();
  215. break;
  216. };
  217. case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
  218. mavlink_param_request_read_t pkt;
  219. mavlink_msg_param_request_read_decode(&msg, &pkt);
  220. const Parameters::Param *p;
  221. if (pkt.param_index < 0) {
  222. p = g.find(pkt.param_id);
  223. } else {
  224. p = g.find_by_index_float(pkt.param_index);
  225. }
  226. float value;
  227. if (!p || !p->get_as_float(value)) {
  228. return;
  229. }
  230. if (p != nullptr && (p->flags & PARAM_FLAG_HIDDEN)) {
  231. return;
  232. }
  233. mavlink_msg_param_value_send(chan,
  234. p->name, value,
  235. MAV_PARAM_TYPE_REAL32,
  236. g.param_count_float(),
  237. g.param_index_float(p));
  238. break;
  239. }
  240. case MAVLINK_MSG_ID_PARAM_SET: {
  241. mavlink_param_set_t pkt;
  242. mavlink_msg_param_set_decode(&msg, &pkt);
  243. auto *p = g.find(pkt.param_id);
  244. float value;
  245. if (pkt.param_type != MAV_PARAM_TYPE_REAL32 ||
  246. !p || !p->get_as_float(value)) {
  247. return;
  248. }
  249. p->get_as_float(value);
  250. if (g.lock_level > 0 &&
  251. (strcmp(p->name, "LOCK_LEVEL") != 0 ||
  252. uint8_t(pkt.param_value) <= uint8_t(value))) {
  253. // only param set allowed is to increase lock level
  254. mav_printf(MAV_SEVERITY_ERROR, "Parameters locked");
  255. } else {
  256. p->set_as_float(pkt.param_value);
  257. }
  258. p->get_as_float(value);
  259. mavlink_msg_param_value_send(chan,
  260. p->name, value,
  261. MAV_PARAM_TYPE_REAL32,
  262. g.param_count_float(),
  263. g.param_index_float(p));
  264. break;
  265. }
  266. case MAVLINK_MSG_ID_SECURE_COMMAND:
  267. case MAVLINK_MSG_ID_SECURE_COMMAND_REPLY: {
  268. mavlink_secure_command_t pkt;
  269. mavlink_msg_secure_command_decode(&msg, &pkt);
  270. handle_secure_command(pkt);
  271. break;
  272. }
  273. default:
  274. // we don't care about other packets
  275. break;
  276. }
  277. }
  278. void MAVLinkSerial::arm_status_send(void)
  279. {
  280. const uint8_t status = parse_fail==nullptr?MAV_ODID_ARM_STATUS_GOOD_TO_ARM:MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
  281. const char *reason = parse_fail==nullptr?"":parse_fail;
  282. mavlink_msg_open_drone_id_arm_status_send(
  283. chan,
  284. status,
  285. reason);
  286. }