MissionItemProtocol.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329
  1. #include "MissionItemProtocol.h"
  2. #include "GCS.h"
  3. void MissionItemProtocol::init_send_requests(GCS_MAVLINK &_link,
  4. const mavlink_message_t &msg,
  5. const int16_t _request_first,
  6. const int16_t _request_last)
  7. {
  8. // set variables to help handle the expected receiving of commands from the GCS
  9. timelast_receive_ms = AP_HAL::millis(); // set time we last received commands to now
  10. receiving = true; // record that we expect to receive commands
  11. request_i = _request_first; // reset the next expected command number to zero
  12. request_last = _request_last; // record how many commands we expect to receive
  13. dest_sysid = msg.sysid; // record system id of GCS who wants to upload the mission
  14. dest_compid = msg.compid; // record component id of GCS who wants to upload the mission
  15. link = &_link;
  16. timelast_request_ms = AP_HAL::millis();
  17. link->send_message(next_item_ap_message_id());
  18. }
  19. void MissionItemProtocol::handle_mission_clear_all(const GCS_MAVLINK &_link,
  20. const mavlink_message_t &msg)
  21. {
  22. bool success = true;
  23. success = success && !receiving;
  24. success = success && clear_all_items();
  25. send_mission_ack(_link, msg, success ? MAV_MISSION_ACCEPTED : MAV_MISSION_ERROR);
  26. }
  27. bool MissionItemProtocol::mavlink2_requirement_met(const GCS_MAVLINK &_link, const mavlink_message_t &msg) const
  28. {
  29. // need mavlink2 to do mission types other than mission:
  30. if (mission_type() == MAV_MISSION_TYPE_MISSION) {
  31. return true;
  32. }
  33. if (!_link.sending_mavlink1()) {
  34. return true;
  35. }
  36. gcs().send_text(MAV_SEVERITY_WARNING, "Need mavlink2 for item transfer");
  37. send_mission_ack(_link, msg, MAV_MISSION_UNSUPPORTED);
  38. return false;
  39. }
  40. void MissionItemProtocol::handle_mission_count(
  41. GCS_MAVLINK &_link,
  42. const mavlink_mission_count_t &packet,
  43. const mavlink_message_t &msg)
  44. {
  45. if (!mavlink2_requirement_met(_link, msg)) {
  46. return;
  47. }
  48. if (receiving) {
  49. // someone is already uploading a mission. If we are
  50. // receiving from someone then we will allow them to restart -
  51. // otherwise we deny.
  52. if (msg.sysid != dest_sysid || msg.compid != dest_compid) {
  53. // reject another upload until
  54. send_mission_ack(_link, msg, MAV_MISSION_DENIED);
  55. return;
  56. }
  57. }
  58. if (packet.count > max_items()) {
  59. send_mission_ack(_link, msg, MAV_MISSION_NO_SPACE);
  60. return;
  61. }
  62. truncate(packet);
  63. if (packet.count == 0) {
  64. // no requests to send...
  65. const MAV_MISSION_RESULT result = complete(_link);
  66. send_mission_ack(_link, msg, result);
  67. return;
  68. }
  69. // start waypoint receiving
  70. init_send_requests(_link, msg, 0, packet.count-1);
  71. }
  72. void MissionItemProtocol::handle_mission_request_list(
  73. const GCS_MAVLINK &_link,
  74. const mavlink_mission_request_list_t &packet,
  75. const mavlink_message_t &msg)
  76. {
  77. if (!mavlink2_requirement_met(_link, msg)) {
  78. return;
  79. }
  80. if (receiving) {
  81. // someone is uploading a mission; reject fetching of points
  82. // until done or timeout
  83. send_mission_ack(_link, msg, MAV_MISSION_DENIED);
  84. return;
  85. }
  86. // reply with number of commands in the mission. The GCS will
  87. // then request each command separately
  88. mavlink_msg_mission_count_send(_link.get_chan(),
  89. msg.sysid,
  90. msg.compid,
  91. item_count(),
  92. mission_type());
  93. }
  94. void MissionItemProtocol::handle_mission_request_int(const GCS_MAVLINK &_link,
  95. const mavlink_mission_request_int_t &packet,
  96. const mavlink_message_t &msg)
  97. {
  98. if (!mavlink2_requirement_met(_link, msg)) {
  99. return;
  100. }
  101. if (receiving) {
  102. // someone is uploading a mission; reject fetching of points
  103. // until done or timeout
  104. send_mission_ack(_link, msg, MAV_MISSION_DENIED);
  105. return;
  106. }
  107. mavlink_mission_item_int_t ret_packet{};
  108. ret_packet.target_system = msg.sysid;
  109. ret_packet.target_component = msg.compid;
  110. ret_packet.seq = packet.seq;
  111. ret_packet.mission_type = packet.mission_type;
  112. const MAV_MISSION_RESULT result_code = get_item(_link, msg, packet, ret_packet);
  113. if (result_code != MAV_MISSION_ACCEPTED) {
  114. // send failure message
  115. send_mission_ack(_link, msg, result_code);
  116. return;
  117. }
  118. _link.send_message(MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char*)&ret_packet);
  119. }
  120. void MissionItemProtocol::handle_mission_request(const GCS_MAVLINK &_link,
  121. const mavlink_mission_request_t &packet,
  122. const mavlink_message_t &msg
  123. )
  124. {
  125. if (!mavlink2_requirement_met(_link, msg)) {
  126. return;
  127. }
  128. // convert into a MISSION_REQUEST_INT and reuse its handling code
  129. mavlink_mission_request_int_t request_int;
  130. request_int.target_system = packet.target_system;
  131. request_int.target_component = packet.target_component;
  132. request_int.seq = packet.seq;
  133. request_int.mission_type = packet.mission_type;
  134. mavlink_mission_item_int_t item_int{};
  135. item_int.target_system = msg.sysid;
  136. item_int.target_component = msg.compid;
  137. item_int.mission_type = packet.mission_type;
  138. item_int.seq = packet.seq;
  139. MAV_MISSION_RESULT ret = get_item(_link, msg, request_int, item_int);
  140. if (ret != MAV_MISSION_ACCEPTED) {
  141. send_mission_ack(_link, msg, ret);
  142. return;
  143. }
  144. mavlink_mission_item_t ret_packet{};
  145. ret = AP_Mission::convert_MISSION_ITEM_INT_to_MISSION_ITEM(item_int, ret_packet);
  146. if (ret != MAV_MISSION_ACCEPTED) {
  147. send_mission_ack(_link, msg, ret);
  148. return;
  149. }
  150. _link.send_message(MAVLINK_MSG_ID_MISSION_ITEM, (const char*)&ret_packet);
  151. }
  152. void MissionItemProtocol::handle_mission_write_partial_list(GCS_MAVLINK &_link,
  153. const mavlink_message_t &msg,
  154. const mavlink_mission_write_partial_list_t &packet)
  155. {
  156. // start waypoint receiving
  157. if ((unsigned)packet.start_index > item_count() ||
  158. (unsigned)packet.end_index > item_count() ||
  159. packet.end_index < packet.start_index) {
  160. gcs().send_text(MAV_SEVERITY_WARNING,"Flight plan update rejected"); // FIXME: Remove this anytime after 2020-01-22
  161. send_mission_ack(_link, msg, MAV_MISSION_ERROR);
  162. return;
  163. }
  164. init_send_requests(_link, msg, packet.start_index, packet.end_index);
  165. }
  166. void MissionItemProtocol::handle_mission_item(const mavlink_message_t &msg, const mavlink_mission_item_int_t &cmd)
  167. {
  168. if (link == nullptr) {
  169. AP::internalerror().error(AP_InternalError::error_t::gcs_bad_missionprotocol_link);
  170. return;
  171. }
  172. // check if this is the requested waypoint
  173. if (cmd.seq != request_i) {
  174. send_mission_ack(msg, MAV_MISSION_INVALID_SEQUENCE);
  175. return;
  176. }
  177. // make sure the item is coming from the system that initiated the upload
  178. if (msg.sysid != dest_sysid) {
  179. send_mission_ack(msg, MAV_MISSION_DENIED);
  180. return;
  181. }
  182. if (msg.compid != dest_compid) {
  183. send_mission_ack(msg, MAV_MISSION_DENIED);
  184. return;
  185. }
  186. const uint16_t _item_count = item_count();
  187. MAV_MISSION_RESULT result;
  188. if (cmd.seq < _item_count) {
  189. // command index is within the existing list, replace the command
  190. result = replace_item(cmd);
  191. } else if (cmd.seq == _item_count) {
  192. // command is at the end of command list, add the command
  193. result = append_item(cmd);
  194. } else {
  195. // beyond the end of the command list, return an error
  196. result = MAV_MISSION_ERROR;
  197. }
  198. if (result != MAV_MISSION_ACCEPTED) {
  199. send_mission_ack(msg, result);
  200. receiving = false;
  201. link = nullptr;
  202. return;
  203. }
  204. // update waypoint receiving state machine
  205. timelast_receive_ms = AP_HAL::millis();
  206. request_i++;
  207. if (request_i > request_last) {
  208. const MAV_MISSION_RESULT complete_result = complete(*link);
  209. send_mission_ack(msg, complete_result);
  210. receiving = false;
  211. link = nullptr;
  212. return;
  213. }
  214. // if we have enough space, then send the next WP request immediately
  215. if (HAVE_PAYLOAD_SPACE(link->get_chan(), MISSION_REQUEST)) {
  216. queued_request_send();
  217. } else {
  218. link->send_message(next_item_ap_message_id());
  219. }
  220. }
  221. void MissionItemProtocol::send_mission_ack(const mavlink_message_t &msg,
  222. MAV_MISSION_RESULT result) const
  223. {
  224. if (link == nullptr) {
  225. AP::internalerror().error(AP_InternalError::error_t::gcs_bad_missionprotocol_link);
  226. return;
  227. }
  228. send_mission_ack(*link, msg, result);
  229. }
  230. void MissionItemProtocol::send_mission_ack(const GCS_MAVLINK &_link,
  231. const mavlink_message_t &msg,
  232. MAV_MISSION_RESULT result) const
  233. {
  234. mavlink_msg_mission_ack_send(_link.get_chan(),
  235. msg.sysid,
  236. msg.compid,
  237. result,
  238. mission_type());
  239. }
  240. /**
  241. * @brief Send the next pending waypoint, called from deferred message
  242. * handling code
  243. */
  244. void MissionItemProtocol::queued_request_send()
  245. {
  246. if (!receiving) {
  247. return;
  248. }
  249. if (request_i > request_last) {
  250. return;
  251. }
  252. if (link == nullptr) {
  253. AP::internalerror().error(AP_InternalError::error_t::gcs_bad_missionprotocol_link);
  254. return;
  255. }
  256. mavlink_msg_mission_request_send(
  257. link->get_chan(),
  258. dest_sysid,
  259. dest_compid,
  260. request_i,
  261. mission_type());
  262. timelast_request_ms = AP_HAL::millis();
  263. }
  264. void MissionItemProtocol::update()
  265. {
  266. if (!receiving) {
  267. // we don't need to do anything unless we're sending requests
  268. return;
  269. }
  270. if (link == nullptr) {
  271. AP::internalerror().error(AP_InternalError::error_t::gcs_bad_missionprotocol_link);
  272. return;
  273. }
  274. // stop waypoint receiving if timeout
  275. const uint32_t tnow = AP_HAL::millis();
  276. if (tnow - timelast_receive_ms > upload_timeout_ms) {
  277. receiving = false;
  278. timeout();
  279. link = nullptr;
  280. return;
  281. }
  282. // resend request if we haven't gotten one:
  283. const uint32_t wp_recv_timeout_ms = 1000U + (link->get_stream_slowdown_ms()*20);
  284. if (tnow - timelast_request_ms > wp_recv_timeout_ms) {
  285. timelast_request_ms = tnow;
  286. link->send_message(next_item_ap_message_id());
  287. }
  288. }