Skip to content
Snippets Groups Projects
Commit 105e2e19 authored by Randy Mackay's avatar Randy Mackay
Browse files

Copter: skip pre-arm checks when already armed

parent 4033f11a
No related branches found
No related tags found
No related merge requests found
...@@ -215,7 +215,13 @@ static bool init_arm_motors() ...@@ -215,7 +215,13 @@ static bool init_arm_motors()
// perform pre-arm checks and set ap.pre_arm_check flag // perform pre-arm checks and set ap.pre_arm_check flag
static void pre_arm_checks(bool display_failure) static void pre_arm_checks(bool display_failure)
{ {
// exit immediately if already armed
if (motors.armed()) {
return;
}
// exit immediately if we've already successfully performed the pre-arm check // exit immediately if we've already successfully performed the pre-arm check
// run gps checks because results may change and affect LED colour
if (ap.pre_arm_check) { if (ap.pre_arm_check) {
pre_arm_gps_checks(display_failure); pre_arm_gps_checks(display_failure);
return; return;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment