Copter: use ArmingMethod enumeration

This commit is contained in:
Peter Barker 2018-06-25 12:09:23 +10:00 committed by Peter Barker
parent 3cfdcb1f2c
commit df83cb034e
7 changed files with 20 additions and 20 deletions

View File

@ -16,11 +16,11 @@ void AP_Arming_Copter::update(void)
}
// performs pre-arm checks and arming checks
bool AP_Arming_Copter::all_checks_passing(bool arming_from_gcs)
bool AP_Arming_Copter::all_checks_passing(ArmingMethod method)
{
set_pre_arm_check(pre_arm_checks(true));
return copter.ap.pre_arm_check && arm_checks(true, arming_from_gcs);
return copter.ap.pre_arm_check && arm_checks(true, method);
}
// perform pre-arm checks
@ -504,7 +504,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, bool arming_from_gcs)
bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::ArmingMethod method)
{
const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
@ -537,7 +537,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
control_mode_t control_mode = copter.control_mode;
// always check if the current mode allows arming
if (!copter.flightmode->allows_arming(arming_from_gcs)) {
if (!copter.flightmode->allows_arming(method == AP_Arming::ArmingMethod::MAVLINK)) {
check_failed(ARMING_CHECK_NONE, display_failure, "Mode not armable");
return false;
}
@ -601,7 +601,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
}
// check throttle is not too high - skips checks if arming from GCS in Guided
if (!(arming_from_gcs && (control_mode == GUIDED || control_mode == GUIDED_NOGPS))) {
if (!(method == AP_Arming::ArmingMethod::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);
@ -624,7 +624,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
// superclass method should always be the last thing called; it
// has side-effects which would need to be cleaned up if one of
// our arm checks failed
return AP_Arming::arm_checks(arming_from_gcs);
return AP_Arming::arm_checks(method);
}
void AP_Arming_Copter::set_pre_arm_check(bool b)

View File

@ -20,7 +20,7 @@ public:
AP_Arming_Copter &operator=(const AP_Arming_Copter&) = delete;
void update(void);
bool all_checks_passing(bool arming_from_gcs);
bool all_checks_passing(ArmingMethod 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, bool arming_from_gcs);
bool arm_checks(bool display_failure, AP_Arming::ArmingMethod method);
// NOTE! the following check functions *DO* call into AP_Arming:
bool ins_checks(bool display_failure) override;

View File

@ -833,7 +833,7 @@ private:
// motors.cpp
void arm_motors_check();
void auto_disarm_check();
bool init_arm_motors(bool arming_from_gcs, bool do_arming_checks=true);
bool init_arm_motors(AP_Arming::ArmingMethod method, bool do_arming_checks=true);
void init_disarm_motors();
void motors_output();
void lost_vehicle_check();

View File

@ -963,7 +963,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
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(true, do_arming_checks)) {
if (copter.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK, do_arming_checks)) {
result = MAV_RESULT_ACCEPTED;
}
} else if (is_zero(packet.param1)) {
@ -1094,7 +1094,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
if (!copter.motors->armed()) {
// if disarmed, arm motors
copter.init_arm_motors(true);
copter.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK);
} else if (copter.ap.land_complete) {
// if armed and landed, takeoff
if (copter.set_mode(LOITER, MODE_REASON_GCS_COMMAND)) {

View File

@ -39,7 +39,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(false)) {
if (!init_arm_motors(AP_Arming::ArmingMethod::RUDDER)) {
arming_counter = 0;
}
}
@ -127,7 +127,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 bool arming_from_gcs, const bool do_arming_checks)
bool Copter::init_arm_motors(const AP_Arming::ArmingMethod method, const bool do_arming_checks)
{
static bool in_arm_motors = false;
@ -144,7 +144,7 @@ bool Copter::init_arm_motors(const bool arming_from_gcs, const bool do_arming_ch
}
// run pre-arm-checks and display failures
if (do_arming_checks && !arming.all_checks_passing(arming_from_gcs)) {
if (do_arming_checks && !arming.all_checks_passing(method)) {
AP_Notify::events.arming_failed = true;
in_arm_motors = false;
return false;

View File

@ -637,7 +637,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
// arm or disarm the vehicle
switch (ch_flag) {
case AUX_SWITCH_HIGH:
init_arm_motors(false);
init_arm_motors(AP_Arming::ArmingMethod::AUXSWITCH);
// remember that we are using an arming switch, for use by set_throttle_zero_flag
ap.armed_with_switch = true;
break;

View File

@ -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(true) && (flags & FLAG_UPGRADE_LOITER) && copter.control_mode == LOITER) {
if (!copter.init_arm_motors(AP_Arming::ArmingMethod::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(true)) {
if (!copter.init_arm_motors(AP_Arming::ArmingMethod::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(true)) {
if (copter.init_arm_motors(AP_Arming::ArmingMethod::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(false);
copter.init_arm_motors(AP_Arming::ArmingMethod::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(false);
copter.init_arm_motors(AP_Arming::ArmingMethod::RUDDER);
if (!copter.motors->armed()) {
AP_Notify::events.arming_failed = true;
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: non-GPS arming failed");