mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: use enum class for ArmingMethod and ArmingRequired
This commit is contained in:
parent
0dacf78c12
commit
f189860162
@ -16,7 +16,7 @@ void AP_Arming_Copter::update(void)
|
||||
}
|
||||
|
||||
// performs pre-arm checks and arming checks
|
||||
bool AP_Arming_Copter::all_checks_passing(ArmingMethod method)
|
||||
bool AP_Arming_Copter::all_checks_passing(AP_Arming::Method method)
|
||||
{
|
||||
set_pre_arm_check(pre_arm_checks(true));
|
||||
|
||||
@ -443,7 +443,7 @@ bool AP_Arming_Copter::pre_arm_proximity_check(bool display_failure)
|
||||
// arm_checks - perform final checks before arming
|
||||
// always called just before arming. Return true if ok to arm
|
||||
// has side-effect that logging is started
|
||||
bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::ArmingMethod method)
|
||||
bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method)
|
||||
{
|
||||
const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
|
||||
|
||||
@ -476,7 +476,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::ArmingMethod
|
||||
control_mode_t control_mode = copter.control_mode;
|
||||
|
||||
// always check if the current mode allows arming
|
||||
if (!copter.flightmode->allows_arming(method == AP_Arming::ArmingMethod::MAVLINK)) {
|
||||
if (!copter.flightmode->allows_arming(method == AP_Arming::Method::MAVLINK)) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "Mode not armable");
|
||||
return false;
|
||||
}
|
||||
@ -540,7 +540,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::ArmingMethod
|
||||
}
|
||||
|
||||
// check throttle is not too high - skips checks if arming from GCS in Guided
|
||||
if (!(method == AP_Arming::ArmingMethod::MAVLINK && (control_mode == GUIDED || control_mode == GUIDED_NOGPS))) {
|
||||
if (!(method == AP_Arming::Method::MAVLINK && (control_mode == GUIDED || control_mode == GUIDED_NOGPS))) {
|
||||
// above top of deadband is too always high
|
||||
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
|
||||
check_failed(ARMING_CHECK_RC, display_failure, "%s too high", rc_item);
|
||||
|
@ -12,7 +12,7 @@ public:
|
||||
{
|
||||
// default REQUIRE parameter to 1 (Copter does not have an
|
||||
// actual ARMING_REQUIRE parameter)
|
||||
require.set_default(YES_MIN_PWM);
|
||||
require.set_default((uint8_t)Required::YES_MIN_PWM);
|
||||
}
|
||||
|
||||
/* Do not allow copies */
|
||||
@ -20,7 +20,7 @@ public:
|
||||
AP_Arming_Copter &operator=(const AP_Arming_Copter&) = delete;
|
||||
|
||||
void update(void);
|
||||
bool all_checks_passing(ArmingMethod method);
|
||||
bool all_checks_passing(AP_Arming::Method method);
|
||||
|
||||
bool rc_calibration_checks(bool display_failure) override;
|
||||
|
||||
@ -30,7 +30,7 @@ protected:
|
||||
bool pre_arm_ekf_attitude_check();
|
||||
bool pre_arm_terrain_check(bool display_failure);
|
||||
bool pre_arm_proximity_check(bool display_failure);
|
||||
bool arm_checks(bool display_failure, AP_Arming::ArmingMethod method);
|
||||
bool arm_checks(bool display_failure, AP_Arming::Method method);
|
||||
|
||||
// NOTE! the following check functions *DO* call into AP_Arming:
|
||||
bool ins_checks(bool display_failure) override;
|
||||
|
@ -770,7 +770,7 @@ private:
|
||||
// motors.cpp
|
||||
void arm_motors_check();
|
||||
void auto_disarm_check();
|
||||
bool init_arm_motors(AP_Arming::ArmingMethod method, bool do_arming_checks=true);
|
||||
bool init_arm_motors(AP_Arming::Method method, bool do_arming_checks=true);
|
||||
void init_disarm_motors();
|
||||
void motors_output();
|
||||
void lost_vehicle_check();
|
||||
|
@ -708,7 +708,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
// attempt to arm and return success or failure
|
||||
const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value);
|
||||
if (copter.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK, do_arming_checks)) {
|
||||
if (copter.init_arm_motors(AP_Arming::Method::MAVLINK, do_arming_checks)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
} else if (is_zero(packet.param1)) {
|
||||
@ -824,7 +824,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
|
||||
if (!copter.motors->armed()) {
|
||||
// if disarmed, arm motors
|
||||
copter.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK);
|
||||
copter.init_arm_motors(AP_Arming::Method::MAVLINK);
|
||||
} else if (copter.ap.land_complete) {
|
||||
// if armed and landed, takeoff
|
||||
if (copter.set_mode(LOITER, MODE_REASON_GCS_COMMAND)) {
|
||||
|
@ -404,7 +404,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
// arm or disarm the vehicle
|
||||
switch (ch_flag) {
|
||||
case HIGH:
|
||||
copter.init_arm_motors(AP_Arming::ArmingMethod::AUXSWITCH);
|
||||
copter.init_arm_motors(AP_Arming::Method::AUXSWITCH);
|
||||
// remember that we are using an arming switch, for use by set_throttle_zero_flag
|
||||
copter.ap.armed_with_switch = true;
|
||||
break;
|
||||
|
@ -14,8 +14,8 @@ void Copter::arm_motors_check()
|
||||
static int16_t arming_counter;
|
||||
|
||||
// check if arming/disarm using rudder is allowed
|
||||
AP_Arming::ArmingRudder arming_rudder = arming.get_rudder_arming_type();
|
||||
if (arming_rudder == AP_Arming::ARMING_RUDDER_DISABLED) {
|
||||
AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();
|
||||
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -45,7 +45,7 @@ void Copter::arm_motors_check()
|
||||
// arm the motors and configure for flight
|
||||
if (arming_counter == ARM_DELAY && !motors->armed()) {
|
||||
// reset arming counter if arming fail
|
||||
if (!init_arm_motors(AP_Arming::ArmingMethod::RUDDER)) {
|
||||
if (!init_arm_motors(AP_Arming::Method::RUDDER)) {
|
||||
arming_counter = 0;
|
||||
}
|
||||
}
|
||||
@ -58,7 +58,7 @@ void Copter::arm_motors_check()
|
||||
}
|
||||
|
||||
// full left and rudder disarming is enabled
|
||||
} else if ((yaw_in < -4000) && (arming_rudder == AP_Arming::ARMING_RUDDER_ARMDISARM)) {
|
||||
} else if ((yaw_in < -4000) && (arming_rudder == AP_Arming::RudderArming::ARMDISARM)) {
|
||||
if (!flightmode->has_manual_throttle() && !ap.land_complete) {
|
||||
arming_counter = 0;
|
||||
return;
|
||||
@ -133,7 +133,7 @@ void Copter::auto_disarm_check()
|
||||
|
||||
// init_arm_motors - performs arming process including initialisation of barometer and gyros
|
||||
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
|
||||
bool Copter::init_arm_motors(const AP_Arming::ArmingMethod method, const bool do_arming_checks)
|
||||
bool Copter::init_arm_motors(const AP_Arming::Method method, const bool do_arming_checks)
|
||||
{
|
||||
static bool in_arm_motors = false;
|
||||
|
||||
|
@ -424,7 +424,7 @@ void ToyMode::update()
|
||||
if (throttle_high_counter >= TOY_LAND_ARM_COUNT) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: throttle arm");
|
||||
arm_check_compass();
|
||||
if (!copter.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK) && (flags & FLAG_UPGRADE_LOITER) && copter.control_mode == LOITER) {
|
||||
if (!copter.init_arm_motors(AP_Arming::Method::MAVLINK) && (flags & FLAG_UPGRADE_LOITER) && copter.control_mode == LOITER) {
|
||||
/*
|
||||
support auto-switching to ALT_HOLD, then upgrade to LOITER once GPS available
|
||||
*/
|
||||
@ -433,7 +433,7 @@ void ToyMode::update()
|
||||
#if AC_FENCE == ENABLED
|
||||
copter.fence.enable(false);
|
||||
#endif
|
||||
if (!copter.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK)) {
|
||||
if (!copter.init_arm_motors(AP_Arming::Method::MAVLINK)) {
|
||||
// go back to LOITER
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: ALT_HOLD arm failed");
|
||||
set_and_remember_mode(LOITER, MODE_REASON_TMODE);
|
||||
@ -625,7 +625,7 @@ void ToyMode::update()
|
||||
#if AC_FENCE == ENABLED
|
||||
copter.fence.enable(false);
|
||||
#endif
|
||||
if (copter.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK)) {
|
||||
if (copter.init_arm_motors(AP_Arming::Method::MAVLINK)) {
|
||||
load_test.running = true;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: load_test on");
|
||||
} else {
|
||||
@ -803,7 +803,7 @@ void ToyMode::action_arm(void)
|
||||
// we want GPS and checks are passing, arm and enable fence
|
||||
copter.fence.enable(true);
|
||||
#endif
|
||||
copter.init_arm_motors(AP_Arming::ArmingMethod::RUDDER);
|
||||
copter.init_arm_motors(AP_Arming::Method::RUDDER);
|
||||
if (!copter.motors->armed()) {
|
||||
AP_Notify::events.arming_failed = true;
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: GPS arming failed");
|
||||
@ -819,7 +819,7 @@ void ToyMode::action_arm(void)
|
||||
// non-GPS mode
|
||||
copter.fence.enable(false);
|
||||
#endif
|
||||
copter.init_arm_motors(AP_Arming::ArmingMethod::RUDDER);
|
||||
copter.init_arm_motors(AP_Arming::Method::RUDDER);
|
||||
if (!copter.motors->armed()) {
|
||||
AP_Notify::events.arming_failed = true;
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: non-GPS arming failed");
|
||||
|
Loading…
Reference in New Issue
Block a user