mirror of https://github.com/ArduPilot/ardupilot
Copter: add Copter::option_enabled(...) replacing bitops vs copter.g2.flight_options
This commit is contained in:
parent
5ca8c0058c
commit
3630e772b1
|
@ -622,11 +622,15 @@ private:
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
enum class FlightOptions {
|
enum class FlightOption : uint32_t {
|
||||||
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
|
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
|
||||||
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
|
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
|
||||||
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
|
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
|
||||||
};
|
};
|
||||||
|
// returns true if option is enabled for this vehicle
|
||||||
|
bool option_is_enabled(FlightOption option) const {
|
||||||
|
return (g2.flight_options & uint32_t(option)) != 0;
|
||||||
|
}
|
||||||
|
|
||||||
static constexpr int8_t _failsafe_priorities[] = {
|
static constexpr int8_t _failsafe_priorities[] = {
|
||||||
(int8_t)FailsafeAction::TERMINATE,
|
(int8_t)FailsafeAction::TERMINATE,
|
||||||
|
|
|
@ -102,7 +102,7 @@ void Copter::thrust_loss_check()
|
||||||
static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed
|
static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed
|
||||||
|
|
||||||
// no-op if suppressed by flight options param
|
// no-op if suppressed by flight options param
|
||||||
if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_THRUST_LOSS_CHECK)) != 0) {
|
if (copter.option_is_enabled(FlightOption::DISABLE_THRUST_LOSS_CHECK)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -171,7 +171,7 @@ void Copter::thrust_loss_check()
|
||||||
// the motors library disables this when it is no longer needed to achieve the commanded output
|
// the motors library disables this when it is no longer needed to achieve the commanded output
|
||||||
|
|
||||||
#if AP_GRIPPER_ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
if ((copter.g2.flight_options & uint32_t(FlightOptions::RELEASE_GRIPPER_ON_THRUST_LOSS)) != 0) {
|
if (copter.option_is_enabled(FlightOption::RELEASE_GRIPPER_ON_THRUST_LOSS)) {
|
||||||
gripper.release();
|
gripper.release();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -182,7 +182,7 @@ void Copter::thrust_loss_check()
|
||||||
void Copter::yaw_imbalance_check()
|
void Copter::yaw_imbalance_check()
|
||||||
{
|
{
|
||||||
// no-op if suppressed by flight options param
|
// no-op if suppressed by flight options param
|
||||||
if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_YAW_IMBALANCE_WARNING)) != 0) {
|
if (copter.option_is_enabled(FlightOption::DISABLE_YAW_IMBALANCE_WARNING)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue