mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
AP_NavEKF: cope with the changed semantics of airspeed.use()
This commit is contained in:
parent
ed0a56cc3c
commit
e8017a5079
@ -3690,14 +3690,16 @@ void NavEKF::SetFlightAndFusionModes()
|
|||||||
// if we are a fly forward type vehicle, then in-air mode can be determined through a combination of speed and height criteria
|
// if we are a fly forward type vehicle, then in-air mode can be determined through a combination of speed and height criteria
|
||||||
if (assume_zero_sideslip()) {
|
if (assume_zero_sideslip()) {
|
||||||
// Evaluate a numerical score that defines the likelihood we are in the air
|
// Evaluate a numerical score that defines the likelihood we are in the air
|
||||||
const AP_Airspeed *airspeed = _ahrs->get_airspeed();
|
|
||||||
float gndSpdSq = sq(velNED[0]) + sq(velNED[1]);
|
float gndSpdSq = sq(velNED[0]) + sq(velNED[1]);
|
||||||
uint8_t inAirSum = 0;
|
uint8_t inAirSum = 0;
|
||||||
bool highGndSpdStage2 = false;
|
bool highGndSpdStage2 = false;
|
||||||
|
|
||||||
// trigger at 8 m/s airspeed
|
// trigger at 8 m/s airspeed
|
||||||
if (airspeed && airspeed->use() && airspeed->get_airspeed() * airspeed->get_EAS2TAS() > 8.0f) {
|
if (_ahrs->airspeed_sensor_enabled()) {
|
||||||
inAirSum++;
|
const AP_Airspeed *airspeed = _ahrs->get_airspeed();
|
||||||
|
if (airspeed->get_airspeed() * airspeed->get_EAS2TAS() > 8.0f) {
|
||||||
|
inAirSum++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// this will trigger during change in baro height
|
// this will trigger during change in baro height
|
||||||
@ -4389,10 +4391,7 @@ void NavEKF::InitialiseVariables()
|
|||||||
// return true if we should use the airspeed sensor
|
// return true if we should use the airspeed sensor
|
||||||
bool NavEKF::useAirspeed(void) const
|
bool NavEKF::useAirspeed(void) const
|
||||||
{
|
{
|
||||||
if (_ahrs->get_airspeed() == NULL) {
|
return _ahrs->airspeed_sensor_enabled();
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return _ahrs->get_airspeed()->use();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// return true if we should use the range finder sensor
|
// return true if we should use the range finder sensor
|
||||||
|
Loading…
Reference in New Issue
Block a user