mirror of https://github.com/ArduPilot/ardupilot
GPS: added set_secondary() function
for preventing notify updates for 2nd GPS
This commit is contained in:
parent
148fd889bc
commit
794cc33e6a
|
@ -36,6 +36,7 @@ GPS::GPS(void) :
|
||||||
last_fix_time(0),
|
last_fix_time(0),
|
||||||
_have_raw_velocity(false),
|
_have_raw_velocity(false),
|
||||||
_last_gps_time(0),
|
_last_gps_time(0),
|
||||||
|
_secondary_gps(false),
|
||||||
_idleTimer(0),
|
_idleTimer(0),
|
||||||
_status(GPS::NO_FIX),
|
_status(GPS::NO_FIX),
|
||||||
_last_ground_speed_cm(0),
|
_last_ground_speed_cm(0),
|
||||||
|
@ -108,8 +109,10 @@ GPS::update(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// update notify with gps status
|
if (!_secondary_gps) {
|
||||||
AP_Notify::flags.gps_status = _status;
|
// update notify with gps status
|
||||||
|
AP_Notify::flags.gps_status = _status;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
|
|
|
@ -146,6 +146,8 @@ public:
|
||||||
// return true if the GPS supports vertical velocity values
|
// return true if the GPS supports vertical velocity values
|
||||||
bool have_vertical_velocity(void) const { return _have_raw_velocity; }
|
bool have_vertical_velocity(void) const { return _have_raw_velocity; }
|
||||||
|
|
||||||
|
void set_secondary(void) { _secondary_gps = true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AP_HAL::UARTDriver *_port; ///< port the GPS is attached to
|
AP_HAL::UARTDriver *_port; ///< port the GPS is attached to
|
||||||
|
|
||||||
|
@ -204,6 +206,9 @@ protected:
|
||||||
// the time we got the last GPS timestamp
|
// the time we got the last GPS timestamp
|
||||||
uint32_t _last_gps_time;
|
uint32_t _last_gps_time;
|
||||||
|
|
||||||
|
// this is a secondary GPS, disable notify updates
|
||||||
|
bool _secondary_gps;
|
||||||
|
|
||||||
// return time in seconds since GPS epoch given time components
|
// return time in seconds since GPS epoch given time components
|
||||||
void _make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
|
void _make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue