mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: init_arm_motors calls pre-arm checks
This reduces a small amount of duplicated code in the pilot initiated arming and GCS initiated arming functions
This commit is contained in:
parent
f4c392c64d
commit
e7f20c04c3
@ -1162,16 +1162,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAV_CMD_COMPONENT_ARM_DISARM:
|
||||
if (packet.param1 == 1.0f) {
|
||||
// run pre_arm_checks and arm_checks and display failures
|
||||
if(pre_arm_checks(true) && arm_checks(true, true)) {
|
||||
if (init_arm_motors()) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
AP_Notify::flags.arming_failed = true; // init_arm_motors function will reset flag back to false
|
||||
result = MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
}else{
|
||||
AP_Notify::flags.arming_failed = true; // init_arm_motors function will reset flag back to false
|
||||
// attempt to arm and return success or failure
|
||||
if (init_arm_motors(false)) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
result = MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
} else if (packet.param1 == 0.0f && (mode_has_manual_throttle(control_mode) || ap.land_complete)) {
|
||||
|
@ -31,17 +31,9 @@ static void arm_motors_check()
|
||||
|
||||
// arm the motors and configure for flight
|
||||
if (arming_counter == ARM_DELAY && !motors.armed()) {
|
||||
// run pre-arm-checks and display failures
|
||||
if(pre_arm_checks(true) && arm_checks(true,false)) {
|
||||
if (!init_arm_motors()) {
|
||||
// reset arming counter if arming fail
|
||||
arming_counter = 0;
|
||||
AP_Notify::flags.arming_failed = true;
|
||||
}
|
||||
}else{
|
||||
// reset arming counter if pre-arm checks fail
|
||||
// reset arming counter if arming fail
|
||||
if (!init_arm_motors(false)) {
|
||||
arming_counter = 0;
|
||||
AP_Notify::flags.arming_failed = true;
|
||||
}
|
||||
}
|
||||
|
||||
@ -100,8 +92,8 @@ static void auto_disarm_check()
|
||||
}
|
||||
|
||||
// init_arm_motors - performs arming process including initialisation of barometer and gyros
|
||||
// returns false in the unlikely case that arming fails (because of a gyro calibration failure)
|
||||
static bool init_arm_motors()
|
||||
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
|
||||
static bool init_arm_motors(bool arming_from_gcs)
|
||||
{
|
||||
// arming marker
|
||||
// Flag used to track if we have armed the motors the first time.
|
||||
@ -109,6 +101,12 @@ static bool init_arm_motors()
|
||||
// which calibrates the IMU
|
||||
static bool did_ground_start = false;
|
||||
|
||||
// run pre-arm-checks and display failures
|
||||
if(!pre_arm_checks(true) || !arm_checks(true, arming_from_gcs)) {
|
||||
AP_Notify::flags.arming_failed = true;
|
||||
return false;
|
||||
}
|
||||
|
||||
// disable cpu failsafe because initialising everything takes a while
|
||||
failsafe_disable();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user