mirror of https://github.com/ArduPilot/ardupilot
Copter: fix motors_checks to AP_Arming
This commit is contained in:
parent
ee9588c674
commit
a52db9f29d
|
@ -297,10 +297,10 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||
}
|
||||
|
||||
// check motor setup was successful
|
||||
bool Copter::motor_checks(bool display_failure)
|
||||
bool AP_Arming_Copter::motor_checks(bool display_failure)
|
||||
{
|
||||
// check motors initialised correctly
|
||||
if (!motors->initialised_ok()) {
|
||||
if (!copter.motors->initialised_ok()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check firmware or FRAME_CLASS");
|
||||
}
|
||||
|
|
|
@ -37,6 +37,7 @@ protected:
|
|||
bool fence_checks(bool display_failure);
|
||||
bool board_voltage_checks(bool display_failure);
|
||||
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);
|
||||
bool rc_calibration_checks(bool display_failure);
|
||||
|
|
Loading…
Reference in New Issue