mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Make setter loop through all instances
For setters where a success boolean is returned, return false if any instance fails.
This commit is contained in:
parent
8baf064317
commit
262c5fe56d
|
@ -704,7 +704,9 @@ void NavEKF2::getTiltError(int8_t instance, float &ang)
|
|||
void NavEKF2::resetGyroBias(void)
|
||||
{
|
||||
if (core) {
|
||||
core[primary].resetGyroBias();
|
||||
for (uint8_t i=0; i<num_cores; i++) {
|
||||
core[i].resetGyroBias();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -715,10 +717,17 @@ void NavEKF2::resetGyroBias(void)
|
|||
// If using a range finder for height no reset is performed and it returns false
|
||||
bool NavEKF2::resetHeightDatum(void)
|
||||
{
|
||||
if (!core) {
|
||||
return false;
|
||||
bool status = true;
|
||||
if (core) {
|
||||
for (uint8_t i=0; i<num_cores; i++) {
|
||||
if (!core[i].resetHeightDatum()) {
|
||||
status = false;
|
||||
}
|
||||
return core[primary].resetHeightDatum();
|
||||
}
|
||||
} else {
|
||||
status = false;
|
||||
}
|
||||
return status;
|
||||
}
|
||||
|
||||
// Commands the EKF to not use GPS.
|
||||
|
|
Loading…
Reference in New Issue