mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: new function to check if arming is allowed in the mode
This commit is contained in:
parent
12ddf341aa
commit
999061704e
@ -72,6 +72,9 @@ public:
|
||||
// returns true if vehicle can be armed or disarmed from the transmitter in this mode
|
||||
virtual bool allows_arming_from_transmitter() { return !is_autopilot_mode(); }
|
||||
|
||||
// returns false if vehicle cannot be armed in this mode
|
||||
virtual bool allows_arming() const { return true; }
|
||||
|
||||
bool allows_stick_mixing() const { return is_autopilot_mode(); }
|
||||
|
||||
//
|
||||
@ -510,6 +513,9 @@ public:
|
||||
// attributes of the mode
|
||||
bool is_autopilot_mode() const override { return true; }
|
||||
|
||||
// do not allow arming from this mode
|
||||
bool allows_arming() const override { return false; }
|
||||
|
||||
// return desired location
|
||||
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;
|
||||
|
||||
@ -542,6 +548,9 @@ public:
|
||||
// attributes of the mode
|
||||
bool is_autopilot_mode() const override { return true; }
|
||||
|
||||
// do not allow arming from this mode
|
||||
bool allows_arming() const override { return false; }
|
||||
|
||||
// return desired location
|
||||
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user