mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_GPS: fixed UAVCAN GPS status when disconnected
this fixes the status reported for a UAVCAN GPS when the cable is unplugged. It should be "NO GPS", but was instead reporting "NO FIX". The user had no way to distinguish between not finding a CAN GPS at all and it not getting satellites thanks to CUAV for reporting
This commit is contained in:
parent
000aa4f515
commit
00260db65a
@ -635,7 +635,7 @@ void AP_GPS::update_instance(uint8_t instance)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
|
if (drivers[instance] == nullptr) {
|
||||||
// we don't yet know the GPS type of this one, or it has timed
|
// we don't yet know the GPS type of this one, or it has timed
|
||||||
// out and needs to be re-initialised
|
// out and needs to be re-initialised
|
||||||
detect_instance(instance);
|
detect_instance(instance);
|
||||||
@ -721,7 +721,7 @@ void AP_GPS::update(void)
|
|||||||
|
|
||||||
// calculate number of instances
|
// calculate number of instances
|
||||||
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
|
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
|
||||||
if (state[i].status != NO_GPS) {
|
if (drivers[i] != nullptr) {
|
||||||
num_instances = i+1;
|
num_instances = i+1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -229,6 +229,15 @@ void AP_GPS_UAVCAN::handle_fix_msg(const FixCb &cb)
|
|||||||
interim_state.last_gps_time_ms = AP_HAL::millis();
|
interim_state.last_gps_time_ms = AP_HAL::millis();
|
||||||
|
|
||||||
_new_data = true;
|
_new_data = true;
|
||||||
|
if (!seen_message) {
|
||||||
|
if (interim_state.status == AP_GPS::GPS_Status::NO_GPS) {
|
||||||
|
// the first time we see a fix message we change from
|
||||||
|
// NO_GPS to NO_FIX, indicating to user that a UAVCAN GPS
|
||||||
|
// has been seen
|
||||||
|
interim_state.status = AP_GPS::GPS_Status::NO_FIX;
|
||||||
|
}
|
||||||
|
seen_message = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_GPS_UAVCAN::handle_aux_msg(const AuxCb &cb)
|
void AP_GPS_UAVCAN::handle_aux_msg(const AuxCb &cb)
|
||||||
@ -275,6 +284,10 @@ bool AP_GPS_UAVCAN::read(void)
|
|||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
if (!seen_message) {
|
||||||
|
// start with NO_GPS until we get first packet
|
||||||
|
state.status = AP_GPS::GPS_Status::NO_GPS;
|
||||||
|
}
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -57,6 +57,7 @@ private:
|
|||||||
HAL_Semaphore sem;
|
HAL_Semaphore sem;
|
||||||
|
|
||||||
uint8_t _detected_module;
|
uint8_t _detected_module;
|
||||||
|
bool seen_message;
|
||||||
|
|
||||||
// Module Detection Registry
|
// Module Detection Registry
|
||||||
static struct DetectedModules {
|
static struct DetectedModules {
|
||||||
|
Loading…
Reference in New Issue
Block a user