mirror of https://github.com/ArduPilot/ardupilot
Copter: add and use private ModeAuto::option_is_enabled method
This commit is contained in:
parent
7e722eeb94
commit
5f9abc0406
|
@ -596,12 +596,13 @@ protected:
|
|||
|
||||
private:
|
||||
|
||||
enum class Options : int32_t {
|
||||
enum class Option : int32_t {
|
||||
AllowArming = (1 << 0U),
|
||||
AllowTakeOffWithoutRaisingThrottle = (1 << 1U),
|
||||
IgnorePilotYaw = (1 << 2U),
|
||||
AllowWeatherVaning = (1 << 7U),
|
||||
};
|
||||
bool option_is_enabled(Option option) const;
|
||||
|
||||
// Enter auto rtl pseudo mode
|
||||
bool enter_auto_rtl(ModeReason reason);
|
||||
|
|
|
@ -202,15 +202,23 @@ void ModeAuto::set_submode(SubMode new_submode)
|
|||
}
|
||||
}
|
||||
|
||||
bool ModeAuto::option_is_enabled(Option option) const
|
||||
{
|
||||
return ((copter.g2.auto_options & (uint32_t)option) != 0);
|
||||
}
|
||||
|
||||
bool ModeAuto::allows_arming(AP_Arming::Method method) const
|
||||
{
|
||||
return ((copter.g2.auto_options & (uint32_t)Options::AllowArming) != 0) && !auto_RTL;
|
||||
};
|
||||
if (auto_RTL) {
|
||||
return false;
|
||||
}
|
||||
return option_is_enabled(Option::AllowArming);
|
||||
}
|
||||
|
||||
#if WEATHERVANE_ENABLED == ENABLED
|
||||
bool ModeAuto::allows_weathervaning() const
|
||||
{
|
||||
return (copter.g2.auto_options & (uint32_t)Options::AllowWeatherVaning) != 0;
|
||||
return option_is_enabled(Option::AllowWeatherVaning);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -638,7 +646,7 @@ void PayloadPlace::start_descent()
|
|||
// returns true if pilot's yaw input should be used to adjust vehicle's heading
|
||||
bool ModeAuto::use_pilot_yaw(void) const
|
||||
{
|
||||
const bool allow_yaw_option = (copter.g2.auto_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0;
|
||||
const bool allow_yaw_option = !option_is_enabled(Option::IgnorePilotYaw);
|
||||
const bool rtl_allow_yaw = (_mode == SubMode::RTL) && copter.mode_rtl.use_pilot_yaw();
|
||||
const bool landing = _mode == SubMode::LAND;
|
||||
return allow_yaw_option || rtl_allow_yaw || landing;
|
||||
|
@ -1039,7 +1047,7 @@ void ModeAuto::takeoff_run()
|
|||
{
|
||||
// if the user doesn't want to raise the throttle we can set it automatically
|
||||
// note that this can defeat the disarm check on takeoff
|
||||
if ((copter.g2.auto_options & (int32_t)Options::AllowTakeOffWithoutRaisingThrottle) != 0) {
|
||||
if (option_is_enabled(Option::AllowTakeOffWithoutRaisingThrottle)) {
|
||||
copter.set_auto_armed(true);
|
||||
}
|
||||
auto_takeoff.run();
|
||||
|
|
Loading…
Reference in New Issue