MissionItemProtocol_Waypoints.h 2.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768
  1. #pragma once
  2. #include "MissionItemProtocol.h"
  3. class MissionItemProtocol_Waypoints : public MissionItemProtocol {
  4. public:
  5. MissionItemProtocol_Waypoints(class AP_Mission &_mission) :
  6. mission(_mission) {}
  7. // mission_type returns the MAV_MISSION mavlink enumeration value
  8. // which this module is responsible for handling
  9. MAV_MISSION_TYPE mission_type() const override {
  10. return MAV_MISSION_TYPE_MISSION;
  11. }
  12. // complete() is called by the base class after all waypoints have
  13. // been received. _link is the link which the last item was
  14. // transfered on.
  15. MAV_MISSION_RESULT complete(const GCS_MAVLINK &_link) override;
  16. // timeout() is called by the base class in the case that the GCS
  17. // does not transfer all waypoints to the vehicle.
  18. void timeout() override;
  19. // truncate() is called to set the absolute number of items. It
  20. // must be less than or equal to the current number of items (you
  21. // can't truncate-to a longer list)
  22. void truncate(const mavlink_mission_count_t &packet) override;
  23. protected:
  24. // clear_all_items() is called to clear all items on the vehicle
  25. bool clear_all_items() override WARN_IF_UNUSED;
  26. // next_item_ap_message_id returns an item from the ap_message
  27. // enumeration which (when acted upon by the GCS class) will send
  28. // a mavlink message to the GCS requesting it upload the next
  29. // required waypoint.
  30. ap_message next_item_ap_message_id() const override {
  31. return MSG_NEXT_MISSION_REQUEST_WAYPOINTS;
  32. }
  33. private:
  34. AP_Mission &mission;
  35. // append_item() is called by the base class to add the supplied
  36. // item to the end of the list of stored items.
  37. MAV_MISSION_RESULT append_item(const mavlink_mission_item_int_t &) override WARN_IF_UNUSED;
  38. // get_item() fills in ret_packet based on packet; _link is the
  39. // link the request was received on, and msg is the undecoded
  40. // request. Note that msg may not actually decode to a
  41. // request_int_t!
  42. MAV_MISSION_RESULT get_item(const GCS_MAVLINK &_link,
  43. const mavlink_message_t &msg,
  44. const mavlink_mission_request_int_t &packet,
  45. mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED;
  46. // item_count() returns the number of stored items
  47. uint16_t item_count() const override;
  48. // item_count() returns the maximum number of items which could be
  49. // stored on-board
  50. uint16_t max_items() const override;
  51. // replace_item() replaces an item in the stored list
  52. MAV_MISSION_RESULT replace_item(const mavlink_mission_item_int_t &) override WARN_IF_UNUSED;
  53. };