MissionItemProtocol.h 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115
  1. #pragma once
  2. #include "GCS_MAVLink.h"
  3. #include "ap_message.h"
  4. #include <stdint.h>
  5. // MissionItemProtocol objects are used for transfering missions from
  6. // a GCS to ArduPilot and vice-versa.
  7. //
  8. // There exists one MissionItemProtocol instance for each of the types
  9. // of item that might be transfered - e.g. MissionItemProtocol_Rally
  10. // for rally point uploads. These objects are static in GCS_MAVLINK
  11. // and used by all of the backends.
  12. //
  13. // While prompting the GCS for items required to complete the mission,
  14. // a link is stored to the link the MissionItemProtocol should send
  15. // requests out on, and the "receiving" boolean is true. In this
  16. // state downloading of items (and the item count!) is blocked.
  17. // Starting of uploads (for the same protocol) is also blocked -
  18. // essentially the GCS uploading a set of items (e.g. a mission) has a
  19. // mutex over the mission.
  20. class MissionItemProtocol
  21. {
  22. public:
  23. // note that all of these methods are named after the packet they
  24. // are handling; the "mission" part just comes as part of that.
  25. void handle_mission_request_list(const class GCS_MAVLINK &link,
  26. const mavlink_mission_request_list_t &packet,
  27. const mavlink_message_t &msg);
  28. void handle_mission_request_int(const GCS_MAVLINK &link,
  29. const mavlink_mission_request_int_t &packet,
  30. const mavlink_message_t &msg);
  31. void handle_mission_request(const GCS_MAVLINK &link,
  32. const mavlink_mission_request_t &packet,
  33. const mavlink_message_t &msg);
  34. void handle_mission_count(class GCS_MAVLINK &link,
  35. const mavlink_mission_count_t &packet,
  36. const mavlink_message_t &msg);
  37. void handle_mission_write_partial_list(GCS_MAVLINK &link,
  38. const mavlink_message_t &msg,
  39. const mavlink_mission_write_partial_list_t &packet);
  40. // called on receipt of a MISSION_ITEM or MISSION_ITEM_INT packet;
  41. // the former is converted to the latter.
  42. void handle_mission_item(const mavlink_message_t &msg,
  43. const mavlink_mission_item_int_t &cmd);
  44. void handle_mission_clear_all(const GCS_MAVLINK &link,
  45. const mavlink_message_t &msg);
  46. void queued_request_send();
  47. void update();
  48. bool active_link_is(const GCS_MAVLINK *_link) const { return _link == link; };
  49. virtual MAV_MISSION_TYPE mission_type() const = 0;
  50. bool receiving; // currently sending requests and expecting items
  51. protected:
  52. GCS_MAVLINK *link; // link currently receiving waypoints on
  53. // return the ap_message which can be queued to be sent to send a
  54. // item request to the GCS:
  55. virtual ap_message next_item_ap_message_id() const = 0;
  56. virtual bool clear_all_items() = 0;
  57. uint16_t request_last; // last request index
  58. private:
  59. virtual void truncate(const mavlink_mission_count_t &packet) = 0;
  60. uint16_t request_i; // request index
  61. // waypoints
  62. uint8_t dest_sysid; // where to send requests
  63. uint8_t dest_compid; // "
  64. uint32_t timelast_receive_ms;
  65. uint32_t timelast_request_ms;
  66. const uint16_t upload_timeout_ms = 8000;
  67. // support for GCS getting waypoints etc from us:
  68. virtual MAV_MISSION_RESULT get_item(const GCS_MAVLINK &_link,
  69. const mavlink_message_t &msg,
  70. const mavlink_mission_request_int_t &packet,
  71. mavlink_mission_item_int_t &ret_packet) = 0;
  72. void init_send_requests(GCS_MAVLINK &_link,
  73. const mavlink_message_t &msg,
  74. const int16_t _request_first,
  75. const int16_t _request_last);
  76. void send_mission_ack(const mavlink_message_t &msg, MAV_MISSION_RESULT result) const;
  77. void send_mission_ack(const GCS_MAVLINK &link, const mavlink_message_t &msg, MAV_MISSION_RESULT result) const;
  78. virtual uint16_t item_count() const = 0;
  79. virtual uint16_t max_items() const = 0;
  80. virtual MAV_MISSION_RESULT replace_item(const mavlink_mission_item_int_t &mission_item_int) = 0;
  81. virtual MAV_MISSION_RESULT append_item(const mavlink_mission_item_int_t &mission_item_int) = 0;
  82. virtual MAV_MISSION_RESULT complete(const GCS_MAVLINK &_link) {
  83. return MAV_MISSION_ACCEPTED;
  84. };
  85. virtual void timeout() {};
  86. bool mavlink2_requirement_met(const GCS_MAVLINK &_link, const mavlink_message_t &msg) const;
  87. };