mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: cope with UAVCAN GPS that don't provide Aux message
thanks to @VadimZ for the suggestion
This commit is contained in:
parent
0cd737856d
commit
bc7f811ff0
|
@ -240,6 +240,12 @@ void AP_GPS_UAVCAN::handle_fix_msg(const FixCb &cb)
|
|||
interim_state.num_sats = 0;
|
||||
}
|
||||
|
||||
if (!seen_aux) {
|
||||
// if we haven't seen an Aux message then populate vdop and
|
||||
// hdop from pdop. Some GPS modules don't provide the Aux message
|
||||
interim_state.hdop = interim_state.vdop = cb.msg->pdop * 100.0;
|
||||
}
|
||||
|
||||
interim_state.last_gps_time_ms = AP_HAL::millis();
|
||||
|
||||
_new_data = true;
|
||||
|
@ -336,6 +342,12 @@ void AP_GPS_UAVCAN::handle_fix2_msg(const Fix2Cb &cb)
|
|||
interim_state.num_sats = 0;
|
||||
}
|
||||
|
||||
if (!seen_aux) {
|
||||
// if we haven't seen an Aux message then populate vdop and
|
||||
// hdop from pdop. Some GPS modules don't provide the Aux message
|
||||
interim_state.hdop = interim_state.vdop = cb.msg->pdop * 100.0;
|
||||
}
|
||||
|
||||
interim_state.last_gps_time_ms = AP_HAL::millis();
|
||||
|
||||
_new_data = true;
|
||||
|
@ -355,10 +367,12 @@ void AP_GPS_UAVCAN::handle_aux_msg(const AuxCb &cb)
|
|||
WITH_SEMAPHORE(sem);
|
||||
|
||||
if (!uavcan::isNaN(cb.msg->hdop)) {
|
||||
seen_aux = true;
|
||||
interim_state.hdop = cb.msg->hdop * 100.0;
|
||||
}
|
||||
|
||||
if (!uavcan::isNaN(cb.msg->vdop)) {
|
||||
seen_aux = true;
|
||||
interim_state.vdop = cb.msg->vdop * 100.0;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -65,6 +65,7 @@ private:
|
|||
|
||||
bool seen_message;
|
||||
bool seen_fix2;
|
||||
bool seen_aux;
|
||||
|
||||
// Module Detection Registry
|
||||
static struct DetectedModules {
|
||||
|
|
Loading…
Reference in New Issue