mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_GPS: rename pre-arm blending health check
This commit is contained in:
parent
e9c881c668
commit
2002827de3
@ -943,7 +943,7 @@ bool AP_GPS::all_consistent(float &distance) const
|
||||
}
|
||||
|
||||
// pre-arm check of GPS blending. True means healthy or that blending is not being used
|
||||
bool AP_GPS::blend_healthy() const
|
||||
bool AP_GPS::blend_health_check() const
|
||||
{
|
||||
return (_blend_health_counter < 50);
|
||||
}
|
||||
|
@ -345,8 +345,8 @@ public:
|
||||
// pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned
|
||||
bool all_consistent(float &distance) const;
|
||||
|
||||
// pre-arm check of GPS blending. True means healthy or that blending is not being used
|
||||
bool blend_healthy() const;
|
||||
// pre-arm check of GPS blending. False if blending is unhealthy, True if healthy or blending is not being used
|
||||
bool blend_health_check() const;
|
||||
|
||||
// handle sending of initialisation strings to the GPS - only used by backends
|
||||
void send_blob_start(uint8_t instance, const char *_blob, uint16_t size);
|
||||
|
Loading…
Reference in New Issue
Block a user