mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: remove Auto mode's rare use of mode() method
This commit is contained in:
parent
b5c58d5c13
commit
ecad165f86
@ -404,7 +404,7 @@ public:
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(AP_Arming::Method method) const override;
|
||||
bool is_autopilot() const override { return true; }
|
||||
bool in_guided_mode() const override { return mode() == SubMode::NAVGUIDED || mode() == SubMode::NAV_SCRIPT_TIME; }
|
||||
bool in_guided_mode() const override { return _mode == SubMode::NAVGUIDED || _mode == SubMode::NAV_SCRIPT_TIME; }
|
||||
|
||||
// Auto modes
|
||||
enum class SubMode : uint8_t {
|
||||
@ -422,8 +422,6 @@ public:
|
||||
NAV_ATTITUDE_TIME,
|
||||
};
|
||||
|
||||
// Auto
|
||||
SubMode mode() const { return _mode; }
|
||||
|
||||
// pause continue in auto mode
|
||||
bool pause() override;
|
||||
|
@ -695,7 +695,7 @@ void ModeAuto::exit_mission()
|
||||
bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
// only process guided waypoint if we are in guided mode
|
||||
if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && mode() == SubMode::NAVGUIDED)) {
|
||||
if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && _mode == SubMode::NAVGUIDED)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user