Skip to content

Commit

Permalink
Merge pull request PX4#149 from PX4/pr-ekf2FixUnwantedGpsUse
Browse files Browse the repository at this point in the history
EKF: prevent unwanted GPS use
  • Loading branch information
priseborough committed May 23, 2016
2 parents c8c2d6d + 5a40aa2 commit 9f0b990
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion EKF/estimator_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,8 @@ void EstimatorInterface::setMagData(uint64_t time_usec, float *data)
void EstimatorInterface::setGpsData(uint64_t time_usec, struct gps_message *gps)
{
// Limit the GPS data rate to a maximum of 14Hz
if (time_usec - _time_last_gps > 65000) {
bool need_gps = (_params.fusion_mode & MASK_USE_GPS) || (_params.vdist_sensor_type == VDIST_SENSOR_GPS);
if (time_usec - _time_last_gps > 65000 && need_gps) {
gpsSample gps_sample_new = {};
gps_sample_new.time_us = gps->time_usec - _params.gps_delay_ms * 1000;

Expand Down

0 comments on commit 9f0b990

Please sign in to comment.