mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: remove code if blended instance is not available
This commit is contained in:
parent
ae1eb93aec
commit
407cfc22ca
|
@ -618,10 +618,12 @@ bool AP_Arming::gps_checks(bool report)
|
|||
(double)distance_m);
|
||||
return false;
|
||||
}
|
||||
#if defined(GPS_BLENDED_INSTANCE)
|
||||
if (!gps.blend_health_check()) {
|
||||
check_failed(ARMING_CHECK_GPS, report, "GPS blending unhealthy");
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
// check AHRS and GPS are within 10m of each other
|
||||
if (gps.num_sensors() > 0) {
|
||||
|
|
|
@ -470,8 +470,10 @@ void AP_GPS::init(const AP_SerialManager& serial_manager)
|
|||
}
|
||||
_last_instance_swap_ms = 0;
|
||||
|
||||
#if defined(GPS_BLENDED_INSTANCE)
|
||||
// Initialise class variables used to do GPS blending
|
||||
_omega_lpf = 1.0f / constrain_float(_blend_tc, 5.0f, 30.0f);
|
||||
#endif
|
||||
|
||||
// prep the state instance fields
|
||||
for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
|
||||
|
@ -491,11 +493,12 @@ void AP_GPS::init(const AP_SerialManager& serial_manager)
|
|||
// GPS solution is treated as an additional sensor.
|
||||
uint8_t AP_GPS::num_sensors(void) const
|
||||
{
|
||||
if (!_output_is_blended) {
|
||||
return num_instances;
|
||||
} else {
|
||||
#if defined(GPS_BLENDED_INSTANCE)
|
||||
if (_output_is_blended) {
|
||||
return num_instances+1;
|
||||
}
|
||||
#endif
|
||||
return num_instances;
|
||||
}
|
||||
|
||||
bool AP_GPS::speed_accuracy(uint8_t instance, float &sacc) const
|
||||
|
@ -1542,11 +1545,13 @@ bool AP_GPS::all_consistent(float &distance) const
|
|||
return (distance < 50);
|
||||
}
|
||||
|
||||
#if defined(GPS_BLENDED_INSTANCE)
|
||||
// pre-arm check of GPS blending. True means healthy or that blending is not being used
|
||||
bool AP_GPS::blend_health_check() const
|
||||
{
|
||||
return (_blend_health_counter < 50);
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
re-assemble fragmented RTCM data
|
||||
|
|
|
@ -730,6 +730,7 @@ private:
|
|||
void inject_data(const uint8_t *data, uint16_t len);
|
||||
void inject_data(uint8_t instance, const uint8_t *data, uint16_t len);
|
||||
|
||||
#if defined(GPS_BLENDED_INSTANCE)
|
||||
// GPS blending and switching
|
||||
Vector3f _blended_antenna_offset; // blended antenna offset
|
||||
float _blended_lag_sec; // blended receiver lag in seconds
|
||||
|
@ -743,6 +744,7 @@ private:
|
|||
|
||||
// calculate the blended state
|
||||
void calc_blended_state(void);
|
||||
#endif
|
||||
|
||||
bool should_log() const;
|
||||
|
||||
|
|
Loading…
Reference in New Issue