mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
Plane: use enum class for ArmingMethod and ArmingRequired
This commit is contained in:
parent
f189860162
commit
ca7566fff9
@ -281,7 +281,7 @@ void Plane::one_second_loop()
|
||||
// update notify flags
|
||||
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
||||
AP_Notify::flags.pre_arm_gps_check = true;
|
||||
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::NO;
|
||||
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::Required::NO;
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
if (should_log(MASK_LOG_GPS)) {
|
||||
@ -905,7 +905,7 @@ void Plane::disarm_if_autoland_complete()
|
||||
{
|
||||
if (landing.get_disarm_delay() > 0 &&
|
||||
!is_flying() &&
|
||||
arming.arming_required() != AP_Arming::NO &&
|
||||
arming.arming_required() != AP_Arming::Required::NO &&
|
||||
arming.is_armed()) {
|
||||
/* we have auto disarm enabled. See if enough time has passed */
|
||||
if (millis() - auto_state.last_flying_ms >= landing.get_disarm_delay()*1000UL) {
|
||||
|
@ -871,7 +871,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
// run pre_arm_checks and arm_checks and display failures
|
||||
const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value);
|
||||
if (plane.arm_motors(AP_Arming::MAVLINK, do_arming_checks)) {
|
||||
if (plane.arm_motors(AP_Arming::Method::MAVLINK, do_arming_checks)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
|
@ -925,7 +925,7 @@ private:
|
||||
int8_t throttle_percentage(void);
|
||||
void change_arm_state(void);
|
||||
bool disarm_motors(void);
|
||||
bool arm_motors(AP_Arming::ArmingMethod method, bool do_arming_checks=true);
|
||||
bool arm_motors(AP_Arming::Method method, bool do_arming_checks=true);
|
||||
bool auto_takeoff_check(void);
|
||||
void takeoff_calc_roll(void);
|
||||
void takeoff_calc_pitch(void);
|
||||
|
@ -62,7 +62,7 @@ void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const aux_swi
|
||||
// arm or disarm the vehicle
|
||||
switch (ch_flag) {
|
||||
case HIGH:
|
||||
plane.arm_motors(AP_Arming::ArmingMethod::AUXSWITCH, true);
|
||||
plane.arm_motors(AP_Arming::Method::AUXSWITCH, true);
|
||||
break;
|
||||
case MIDDLE:
|
||||
// nothing
|
||||
|
@ -1179,7 +1179,7 @@ void QuadPlane::control_loiter()
|
||||
float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
|
||||
{
|
||||
if (plane.get_throttle_input() <= 0 && !plane.auto_throttle_mode &&
|
||||
plane.arming.get_rudder_arming_type() != AP_Arming::ARMING_RUDDER_DISABLED) {
|
||||
plane.arming.get_rudder_arming_type() != AP_Arming::RudderArming::IS_DISABLED) {
|
||||
// the user may be trying to disarm
|
||||
return 0;
|
||||
}
|
||||
|
@ -40,7 +40,7 @@ void Plane::set_control_channels(void)
|
||||
SRV_Channels::set_angle(SRV_Channel::k_throttleRight, 100);
|
||||
}
|
||||
|
||||
if (!arming.is_armed() && arming.arming_required() == AP_Arming::YES_MIN_PWM) {
|
||||
if (!arming.is_armed() && arming.arming_required() == AP_Arming::Required::YES_MIN_PWM) {
|
||||
SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, have_reverse_thrust()?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
}
|
||||
|
||||
@ -86,7 +86,7 @@ void Plane::init_rc_out_main()
|
||||
|
||||
// setup PX4 to output the min throttle when safety off if arming
|
||||
// is setup for min on disarm
|
||||
if (arming.arming_required() == AP_Arming::YES_MIN_PWM) {
|
||||
if (arming.arming_required() == AP_Arming::Required::YES_MIN_PWM) {
|
||||
SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, have_reverse_thrust()?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
}
|
||||
}
|
||||
@ -112,9 +112,9 @@ void Plane::init_rc_out_aux()
|
||||
*/
|
||||
void Plane::rudder_arm_disarm_check()
|
||||
{
|
||||
AP_Arming::ArmingRudder arming_rudder = arming.get_rudder_arming_type();
|
||||
AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();
|
||||
|
||||
if (arming_rudder == AP_Arming::ARMING_RUDDER_DISABLED) {
|
||||
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
|
||||
//parameter disallows rudder arming/disabling
|
||||
return;
|
||||
}
|
||||
@ -146,14 +146,14 @@ void Plane::rudder_arm_disarm_check()
|
||||
}
|
||||
} else {
|
||||
//time to arm!
|
||||
arm_motors(AP_Arming::RUDDER);
|
||||
arm_motors(AP_Arming::Method::RUDDER);
|
||||
rudder_arm_timer = 0;
|
||||
}
|
||||
} else {
|
||||
// not at full right rudder
|
||||
rudder_arm_timer = 0;
|
||||
}
|
||||
} else if ((arming_rudder == AP_Arming::ARMING_RUDDER_ARMDISARM) && !is_flying()) {
|
||||
} else if ((arming_rudder == AP_Arming::RudderArming::ARMDISARM) && !is_flying()) {
|
||||
// when armed and not flying, full left rudder starts disarming counter
|
||||
if (channel_rudder->get_control_in() < -4000) {
|
||||
uint32_t now = millis();
|
||||
|
@ -370,7 +370,7 @@ void Plane::set_servos_controlled(void)
|
||||
constrain_int16(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), min_throttle, max_throttle));
|
||||
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) {
|
||||
if (arming.arming_required() == AP_Arming::Required::YES_ZERO_PWM) {
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
||||
@ -583,7 +583,7 @@ void Plane::servos_twin_engine_mix(void)
|
||||
throttle_right = constrain_float(throttle - 50 * rudder_dt, 0, 100);
|
||||
}
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) {
|
||||
if (arming.arming_required() == AP_Arming::Required::YES_ZERO_PWM) {
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
||||
} else {
|
||||
@ -687,18 +687,18 @@ void Plane::set_servos(void)
|
||||
//Some ESCs get noisy (beep error msgs) if PWM == 0.
|
||||
//This little segment aims to avoid this.
|
||||
switch (arming.arming_required()) {
|
||||
case AP_Arming::NO:
|
||||
case AP_Arming::Required::NO:
|
||||
//keep existing behavior: do nothing to radio_out
|
||||
//(don't disarm throttle channel even if AP_Arming class is)
|
||||
break;
|
||||
|
||||
case AP_Arming::YES_ZERO_PWM:
|
||||
case AP_Arming::Required::YES_ZERO_PWM:
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_throttle, 0);
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, 0);
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, 0);
|
||||
break;
|
||||
|
||||
case AP_Arming::YES_MIN_PWM:
|
||||
case AP_Arming::Required::YES_MIN_PWM:
|
||||
default:
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0);
|
||||
|
@ -757,7 +757,7 @@ void Plane::change_arm_state(void)
|
||||
/*
|
||||
arm motors
|
||||
*/
|
||||
bool Plane::arm_motors(const AP_Arming::ArmingMethod method, const bool do_arming_checks)
|
||||
bool Plane::arm_motors(const AP_Arming::Method method, const bool do_arming_checks)
|
||||
{
|
||||
if (!arming.arm(method, do_arming_checks)) {
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user