mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
AP_Arming: manual transmitter checks call rc calibration checks
This commit is contained in:
parent
9b52c9b670
commit
25a0e6378e
@ -450,6 +450,11 @@ bool AP_Arming::hardware_safety_check(bool report)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_Arming::rc_calibration_checks(bool report)
|
||||||
|
{
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
bool AP_Arming::manual_transmitter_checks(bool report)
|
bool AP_Arming::manual_transmitter_checks(bool report)
|
||||||
{
|
{
|
||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
@ -462,9 +467,9 @@ bool AP_Arming::manual_transmitter_checks(bool report)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
//TODO verify radio calibration
|
if (!rc_calibration_checks(report)) {
|
||||||
//Requires access to Parameters ... which are implemented a little
|
return false;
|
||||||
//differently for Rover, Plane, and Copter.
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
@ -101,6 +101,8 @@ protected:
|
|||||||
|
|
||||||
virtual bool board_voltage_checks(bool report);
|
virtual bool board_voltage_checks(bool report);
|
||||||
|
|
||||||
|
virtual bool rc_calibration_checks(bool report);
|
||||||
|
|
||||||
bool manual_transmitter_checks(bool report);
|
bool manual_transmitter_checks(bool report);
|
||||||
|
|
||||||
virtual enum HomeState home_status() const = 0;
|
virtual enum HomeState home_status() const = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user