Copter: rc calibration checks are called by AP_Arming

This commit is contained in:
Peter Barker 2017-09-04 14:16:40 +10:00 committed by Randy Mackay
parent 25a0e6378e
commit 818faa92d4
2 changed files with 5 additions and 4 deletions

View File

@ -57,8 +57,7 @@ bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
return true; return true;
} }
return rc_calibration_checks(display_failure) return fence_checks(display_failure)
& fence_checks(display_failure)
& parameter_checks(display_failure) & parameter_checks(display_failure)
& motor_checks(display_failure) & motor_checks(display_failure)
& pilot_throttle_checks(display_failure) & & pilot_throttle_checks(display_failure) &
@ -302,7 +301,9 @@ bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
copter.channel_yaw copter.channel_yaw
}; };
copter.ap.pre_arm_rc_check = rc_checks_copter_sub(display_failure, channels); copter.ap.pre_arm_rc_check = rc_checks_copter_sub(display_failure, channels)
& AP_Arming::rc_calibration_checks(display_failure);
return copter.ap.pre_arm_rc_check; return copter.ap.pre_arm_rc_check;
} }

View File

@ -20,7 +20,7 @@ public:
void update(void); void update(void);
bool all_checks_passing(bool arming_from_gcs); bool all_checks_passing(bool arming_from_gcs);
bool rc_calibration_checks(bool display_failure); bool rc_calibration_checks(bool display_failure) override;
protected: protected: