mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: prevent FPE on zero range with optflow
This commit is contained in:
parent
14cf9b1621
commit
a81590f7ac
|
@ -71,7 +71,7 @@ void SITL_State::_update_flow(void)
|
|||
|
||||
// estimate range to centre of image
|
||||
float range;
|
||||
if (rotmat.c.z > 0.05f) {
|
||||
if (rotmat.c.z > 0.05f && height_agl() > 0) {
|
||||
range = height_agl() / rotmat.c.z;
|
||||
} else {
|
||||
range = 1e38f;
|
||||
|
|
Loading…
Reference in New Issue