mirror of https://github.com/ArduPilot/ardupilot
Copter: add has_user_takeoff in ZigZag mode
This commit is contained in:
parent
36dbba0068
commit
86e9679ebb
|
@ -1786,6 +1786,7 @@ public:
|
||||||
bool has_manual_throttle() const override { return false; }
|
bool has_manual_throttle() const override { return false; }
|
||||||
bool allows_arming(AP_Arming::Method method) const override { return true; }
|
bool allows_arming(AP_Arming::Method method) const override { return true; }
|
||||||
bool is_autopilot() const override { return true; }
|
bool is_autopilot() const override { return true; }
|
||||||
|
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||||
|
|
||||||
// save current position as A or B. If both A and B have been saved move to the one specified
|
// save current position as A or B. If both A and B have been saved move to the one specified
|
||||||
void save_or_move_to_destination(Destination ab_dest);
|
void save_or_move_to_destination(Destination ab_dest);
|
||||||
|
|
Loading…
Reference in New Issue