SITL: cope with more rubbish startup values from JSBSim

This commit is contained in:
Andrew Tridgell 2014-05-04 17:30:10 +10:00
parent c1aa2181dc
commit 4efcae46ab
1 changed files with 1 additions and 1 deletions

View File

@ -382,7 +382,7 @@ void SITL_State::_fdm_input(void)
// prevent bad inputs from SIM from corrupting our state // prevent bad inputs from SIM from corrupting our state
double *v = &_sitl->state.latitude; double *v = &_sitl->state.latitude;
for (uint8_t i=0; i<17; i++) { for (uint8_t i=0; i<17; i++) {
if (isinf(v[i]) || isnan(v[i])) { if (isinf(v[i]) || isnan(v[i]) || fabsf(v[i]) > 1.0e10) {
v[i] = 0; v[i] = 0;
} }
} }