mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_PX4: fixed build with new AnalogIn API
pin settle times not actually implemented on PX4 yet
This commit is contained in:
parent
5ac493908c
commit
9bc48c9894
@ -27,6 +27,10 @@ public:
|
||||
void set_pin(uint8_t p);
|
||||
float voltage_average();
|
||||
|
||||
// stop pins not implemented on PX4 yet
|
||||
void set_stop_pin(uint8_t p) {}
|
||||
void set_settle_time(uint16_t settle_time_ms) {}
|
||||
|
||||
private:
|
||||
// what pin it is attached to
|
||||
int16_t _pin;
|
||||
|
Loading…
Reference in New Issue
Block a user