mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL_Linux: changed ADC logic a bit for Navio 2
- make voltage_average_ratiometric() the same as voltage_average() - make read_latest() the same as voltage_average() wip
This commit is contained in:
parent
3feade792a
commit
60426faa52
@ -62,7 +62,7 @@ float AnalogSource_Navio2::read_average()
|
|||||||
|
|
||||||
float AnalogSource_Navio2::read_latest()
|
float AnalogSource_Navio2::read_latest()
|
||||||
{
|
{
|
||||||
return _value;
|
return voltage_average();
|
||||||
}
|
}
|
||||||
|
|
||||||
float AnalogSource_Navio2::voltage_average()
|
float AnalogSource_Navio2::voltage_average()
|
||||||
@ -84,12 +84,13 @@ float AnalogSource_Navio2::voltage_average()
|
|||||||
|
|
||||||
float AnalogSource_Navio2::voltage_latest()
|
float AnalogSource_Navio2::voltage_latest()
|
||||||
{
|
{
|
||||||
|
read_latest();
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
|
|
||||||
float AnalogSource_Navio2::voltage_average_ratiometric()
|
float AnalogSource_Navio2::voltage_average_ratiometric()
|
||||||
{
|
{
|
||||||
return _value;
|
return voltage_average();
|
||||||
}
|
}
|
||||||
|
|
||||||
AnalogIn_Navio2::AnalogIn_Navio2()
|
AnalogIn_Navio2::AnalogIn_Navio2()
|
||||||
|
Loading…
Reference in New Issue
Block a user