mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_NavEKF: added position observations to static mode
This commit is contained in:
parent
da2c341914
commit
cdbc5a3f35
@ -1091,7 +1091,7 @@ void NavEKF::FuseVelPosNED()
|
||||
observation[5] = -hgtMea;
|
||||
// zero observations if in static mode (used for pre-arm and bench testing)
|
||||
if (staticMode) {
|
||||
for (uint8_t i=0; i<=2; i++) observation[i] = 0.0f;
|
||||
for (uint8_t i=0; i<=5; i++) observation[i] = 0.0f;
|
||||
// cancel static mode (it needs to be set every frame if required)
|
||||
staticMode = false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user