AP_GPS: Set unknown DOP's to UINT16_MAX, rather then 9999
This fixes the MAVLink reporting for unknown dops, and avoids the situation where a GPS driver could report a worse DOP then we could handle. Also corrects an apparent error in the HIL_GPS MAVLink message, where we would always select the unknown dop value rather then provided DOP.
This commit is contained in:
parent
70ed572476
commit
c7a89d5aa0
@ -446,8 +446,8 @@ void AP_GPS::detect_instance(uint8_t instance)
|
||||
|
||||
state[instance].instance = instance;
|
||||
state[instance].status = NO_GPS;
|
||||
state[instance].hdop = 9999;
|
||||
state[instance].vdop = 9999;
|
||||
state[instance].hdop = GPS_UNKNOWN_DOP;
|
||||
state[instance].vdop = GPS_UNKNOWN_DOP;
|
||||
|
||||
switch (_type[instance]) {
|
||||
// by default the sbf/trimble gps outputs no data on its port, until configured.
|
||||
@ -578,8 +578,8 @@ void AP_GPS::update_instance(uint8_t instance)
|
||||
if (_type[instance] == GPS_TYPE_NONE) {
|
||||
// not enabled
|
||||
state[instance].status = NO_GPS;
|
||||
state[instance].hdop = 9999;
|
||||
state[instance].vdop = 9999;
|
||||
state[instance].hdop = GPS_UNKNOWN_DOP;
|
||||
state[instance].vdop = GPS_UNKNOWN_DOP;
|
||||
return;
|
||||
}
|
||||
if (locked_ports & (1U<<instance)) {
|
||||
@ -614,8 +614,8 @@ void AP_GPS::update_instance(uint8_t instance)
|
||||
memset(&state[instance], 0, sizeof(state[instance]));
|
||||
state[instance].instance = instance;
|
||||
state[instance].status = NO_GPS;
|
||||
state[instance].hdop = 9999;
|
||||
state[instance].vdop = 9999;
|
||||
state[instance].hdop = GPS_UNKNOWN_DOP;
|
||||
state[instance].vdop = GPS_UNKNOWN_DOP;
|
||||
timing[instance].last_message_time_ms = tnow;
|
||||
}
|
||||
} else {
|
||||
@ -1255,8 +1255,8 @@ void AP_GPS::calc_blended_state(void)
|
||||
state[GPS_BLENDED_INSTANCE].time_week = 0;
|
||||
state[GPS_BLENDED_INSTANCE].ground_speed = 0.0f;
|
||||
state[GPS_BLENDED_INSTANCE].ground_course = 0.0f;
|
||||
state[GPS_BLENDED_INSTANCE].hdop = 9999;
|
||||
state[GPS_BLENDED_INSTANCE].vdop = 9999;
|
||||
state[GPS_BLENDED_INSTANCE].hdop = GPS_UNKNOWN_DOP;
|
||||
state[GPS_BLENDED_INSTANCE].vdop = GPS_UNKNOWN_DOP;
|
||||
state[GPS_BLENDED_INSTANCE].num_sats = 0;
|
||||
state[GPS_BLENDED_INSTANCE].velocity.zero();
|
||||
state[GPS_BLENDED_INSTANCE].speed_accuracy = 1e6f;
|
||||
|
@ -32,6 +32,7 @@
|
||||
#define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2)
|
||||
#define GPS_RTK_INJECT_TO_ALL 127
|
||||
#define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms
|
||||
#define GPS_UNKNOWN_DOP UINT16_MAX // set unknown DOP's to maximum value, which is also correct for MAVLink
|
||||
|
||||
// the number of GPS leap seconds
|
||||
#define GPS_LEAPSECONDS_MILLIS 18000ULL
|
||||
|
@ -123,8 +123,8 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
|
||||
loc.alt = packet.alt;
|
||||
state.location = loc;
|
||||
state.location.options = 0;
|
||||
state.hdop = MAX(packet.eph, 9999);
|
||||
state.vdop = MAX(packet.epv, 9999);
|
||||
state.hdop = MIN(packet.eph, GPS_UNKNOWN_DOP);
|
||||
state.vdop = MIN(packet.epv, GPS_UNKNOWN_DOP);
|
||||
if (packet.vel < 65535) {
|
||||
state.ground_speed = packet.vel / 100.0f;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user