mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Copter: ahrs only checks position in modes that require it
This commit is contained in:
parent
f6cb0819ef
commit
dc515b87df
@ -511,17 +511,17 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const
|
|||||||
// performs mandatory gps checks. returns true if passed
|
// performs mandatory gps checks. returns true if passed
|
||||||
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
|
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
|
||||||
{
|
{
|
||||||
|
// check if flight mode requires GPS
|
||||||
|
bool mode_requires_gps = copter.flightmode->requires_GPS();
|
||||||
|
|
||||||
// always check if inertial nav has started and is ready
|
// always check if inertial nav has started and is ready
|
||||||
const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
|
const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
|
||||||
char failure_msg[50] = {};
|
char failure_msg[50] = {};
|
||||||
if (!ahrs.pre_arm_check(failure_msg, sizeof(failure_msg))) {
|
if (!ahrs.pre_arm_check(mode_requires_gps, failure_msg, sizeof(failure_msg))) {
|
||||||
check_failed(display_failure, "AHRS: %s", failure_msg);
|
check_failed(display_failure, "AHRS: %s", failure_msg);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// check if flight mode requires GPS
|
|
||||||
bool mode_requires_gps = copter.flightmode->requires_GPS();
|
|
||||||
|
|
||||||
// check if fence requires GPS
|
// check if fence requires GPS
|
||||||
bool fence_requires_gps = false;
|
bool fence_requires_gps = false;
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user