1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768 |
- #pragma once
- #include "MissionItemProtocol.h"
- class MissionItemProtocol_Waypoints : public MissionItemProtocol {
- public:
- MissionItemProtocol_Waypoints(class AP_Mission &_mission) :
- mission(_mission) {}
-
-
- MAV_MISSION_TYPE mission_type() const override {
- return MAV_MISSION_TYPE_MISSION;
- }
-
-
-
- MAV_MISSION_RESULT complete(const GCS_MAVLINK &_link) override;
-
-
- void timeout() override;
-
-
-
- void truncate(const mavlink_mission_count_t &packet) override;
- protected:
-
- bool clear_all_items() override WARN_IF_UNUSED;
-
-
-
-
- ap_message next_item_ap_message_id() const override {
- return MSG_NEXT_MISSION_REQUEST_WAYPOINTS;
- }
- private:
- AP_Mission &mission;
-
-
- MAV_MISSION_RESULT append_item(const mavlink_mission_item_int_t &) override WARN_IF_UNUSED;
-
-
-
-
- MAV_MISSION_RESULT get_item(const GCS_MAVLINK &_link,
- const mavlink_message_t &msg,
- const mavlink_mission_request_int_t &packet,
- mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED;
-
- uint16_t item_count() const override;
-
-
- uint16_t max_items() const override;
-
- MAV_MISSION_RESULT replace_item(const mavlink_mission_item_int_t &) override WARN_IF_UNUSED;
- };
|