mirror of https://github.com/ArduPilot/ardupilot
Copter: prearm baro checks are called in parent class
This commit is contained in:
parent
c129445ff6
commit
30c1a040d7
|
@ -57,8 +57,7 @@ bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
|
|||
return true;
|
||||
}
|
||||
|
||||
return barometer_checks(display_failure)
|
||||
& rc_calibration_checks(display_failure)
|
||||
return rc_calibration_checks(display_failure)
|
||||
& compass_checks(display_failure)
|
||||
& gps_checks(display_failure)
|
||||
& fence_checks(display_failure)
|
||||
|
|
|
@ -34,6 +34,7 @@ protected:
|
|||
bool ins_checks(bool display_failure) override;
|
||||
bool compass_checks(bool display_failure) override;
|
||||
bool gps_checks(bool display_failure) override;
|
||||
bool barometer_checks(bool display_failure) override;
|
||||
|
||||
// NOTE! the following check functions *DO NOT* call into AP_Arming!
|
||||
bool fence_checks(bool display_failure);
|
||||
|
@ -41,7 +42,6 @@ protected:
|
|||
bool parameter_checks(bool display_failure);
|
||||
bool motor_checks(bool display_failure);
|
||||
bool pilot_throttle_checks(bool display_failure);
|
||||
bool barometer_checks(bool display_failure);
|
||||
|
||||
void set_pre_arm_check(bool b);
|
||||
|
||||
|
|
|
@ -83,7 +83,7 @@ protected:
|
|||
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
|
||||
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
|
||||
|
||||
bool barometer_checks(bool report);
|
||||
virtual bool barometer_checks(bool report);
|
||||
|
||||
bool airspeed_checks(bool report);
|
||||
|
||||
|
|
Loading…
Reference in New Issue