forked from Archive/PX4-Autopilot
EKF: strengthen checking of local position status
provides immediate status reporting when dropping out of optical flow mode
This commit is contained in:
parent
31bf342fc1
commit
82920da232
|
@ -364,5 +364,5 @@ void EstimatorInterface::unallocate_buffers()
|
|||
bool EstimatorInterface::local_position_is_valid()
|
||||
{
|
||||
// return true if the position estimate is valid
|
||||
return ((_time_last_imu - _time_last_optflow) < 5e6) || global_position_is_valid();
|
||||
return (((_time_last_imu - _time_last_optflow) < 5e6) && _control_status.flags.opt_flow) || global_position_is_valid();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue