mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: AnalogIn channel gets scale, source gets set_pin
This commit is contained in:
parent
50b765616b
commit
7049934a69
|
@ -7,12 +7,14 @@
|
|||
class AP_HAL::AnalogSource {
|
||||
public:
|
||||
virtual float read() = 0;
|
||||
virtual void set_pin(uint8_t p) = 0;
|
||||
};
|
||||
|
||||
class AP_HAL::AnalogIn {
|
||||
public:
|
||||
virtual void init(void* implspecific) = 0;
|
||||
virtual AP_HAL::AnalogSource* channel(int n) = 0;
|
||||
virtual AP_HAL::AnalogSource* channel(int n, float scale) = 0;
|
||||
};
|
||||
|
||||
#define ANALOG_INPUT_BOARD_VCC 254
|
||||
|
|
Loading…
Reference in New Issue