mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: allow GPS moving baseline rover at 3Hz
users with busy CAN bus often get significiantly lower GPS rates on a moving baseline rover, preventing arming. This PR relaxes the required frame rate as the EKF is quite happy with 3Hz yaw and the yaw is the only data consumed from a moving baseline rover
This commit is contained in:
parent
6fa5d0bec0
commit
39f83c91b3
|
@ -2065,12 +2065,14 @@ bool AP_GPS::is_healthy(uint8_t instance) const
|
|||
#else
|
||||
/*
|
||||
allow two lost frames before declaring the GPS unhealthy, but
|
||||
require the average frame rate to be close to 5Hz. We allow for
|
||||
a bit higher average for a rover due to the packet loss that
|
||||
happens with the RTCMv3 data
|
||||
require the average frame rate to be close to 5Hz.
|
||||
|
||||
We allow for a rate of 3Hz average for a moving baseline rover
|
||||
due to the packet loss that happens with the RTCMv3 data and the
|
||||
fact that the rate of yaw data is not critical
|
||||
*/
|
||||
const uint8_t delay_threshold = 2;
|
||||
const float delay_avg_max = ((_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) || (_type[instance] == GPS_TYPE_UAVCAN_RTK_ROVER))?245:215;
|
||||
const float delay_avg_max = ((_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) || (_type[instance] == GPS_TYPE_UAVCAN_RTK_ROVER))?333:215;
|
||||
const GPS_timing &t = timing[instance];
|
||||
bool delay_ok = (t.delayed_count < delay_threshold) &&
|
||||
t.average_delta_ms < delay_avg_max &&
|
||||
|
|
Loading…
Reference in New Issue