mirror of https://github.com/ArduPilot/ardupilot
AP_ADC_AnalogSource: fixed APM1 build
This commit is contained in:
parent
fe5a4ab710
commit
457ca0b57d
|
@ -28,7 +28,6 @@ float AP_ADC_AnalogSource::voltage_average()
|
|||
return fullscale * 3.3 * 2.44140625e-4f;
|
||||
}
|
||||
|
||||
|
||||
void AP_ADC_AnalogSource::set_pin(uint8_t machtnichts) {
|
||||
/* it would be an error to call this
|
||||
* but for now we'll leave it a no-op. */
|
||||
|
|
|
@ -15,6 +15,7 @@ public:
|
|||
float read_latest(void);
|
||||
void set_pin(uint8_t);
|
||||
float voltage_average();
|
||||
float voltage_latest() { return voltage_average(); }
|
||||
float voltage_average_ratiometric() { return voltage_average(); }
|
||||
|
||||
// stop pins not implemented on ADC yet
|
||||
|
|
Loading…
Reference in New Issue