mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Airspeed: fixed get_temperature on PX4
This commit is contained in:
parent
ccb7dc640d
commit
35791e1f05
@ -76,7 +76,8 @@ bool AP_Airspeed_PX4::get_differential_pressure(float &pressure)
|
||||
// read the temperature
|
||||
bool AP_Airspeed_PX4::get_temperature(float &temperature)
|
||||
{
|
||||
return _temperature;
|
||||
temperature = _temperature;
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
Loading…
Reference in New Issue
Block a user