Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Airspeed: check for baro baro data in SDP3X #18232

Merged
merged 1 commit into from
Aug 9, 2021
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 13 additions & 4 deletions libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,16 +223,25 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press)

AP_Baro *baro = AP_Baro::get_singleton();

if (baro == nullptr) {
return press;
float baro_pressure;
if (baro == nullptr || baro->num_instances() == 0) {
// with no baro assume sea level
baro_pressure = SSL_AIR_PRESSURE;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is actually a terrible assumption on this airspeed sensor. We are FAR safer to declare the sensor unhealthy and not update in this case. The airspeed can be off by a ridiculous margin with this approach.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

A slightly better option would be using the temperature, gps altitude, and baro at launch to determine a pressure altitude.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the reason for this PR is people are using the SDP3xx on AP_Periph nodes that have no other sensors. They were getting NaN as the output. They can't use GPS or baro.
I just ran some tests on a SDP3X with changes to the pressure. I first set it up to be reading 20 m/s at sea level (101325Pa). That required a reading from the sensor of 155.
Then I changed it to 10k feet, with a pressure of 69681. The airspeed changed to 20.9 m/s with the same reading from the sensor.
So with a 10k feet change we have a 0.9 m/s error. I wouldn't call that "terrible"

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's not a good solution, they are much much better off not using those on the periph nodes. Unless we've added back the compensation terms that were dropped to make the processing take less time the sensor is off at 8K DA by approximately 3-5 m/s (I can't recall what it was) with a working baro. With a non working baro compounding that I'd hate to see it on an aircraft.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

supporting an existing sensor is vastly better than giving NaN. I will merge

} else {
baro_pressure = baro->get_pressure();
}

float temperature;
if (!get_temperature(temperature)) {
return press;
// assume 25C if no temperature
temperature = 25;
}

float rho_air = baro->get_pressure() / (ISA_GAS_CONSTANT * (temperature + C_TO_KELVIN));
float rho_air = baro_pressure / (ISA_GAS_CONSTANT * (temperature + C_TO_KELVIN));
if (!is_positive(rho_air)) {
// bad pressure
return press;
}

/*
the constants in the code below come from a calibrated test of
Expand Down