Browse Source

AP_HAL: AnalogIn channel gets scale, source gets set_pin

mission-4.1.18
Pat Hickey 12 years ago committed by Andrew Tridgell
parent
commit
7049934a69
  1. 2
      libraries/AP_HAL/AnalogIn.h

2
libraries/AP_HAL/AnalogIn.h

@ -7,12 +7,14 @@ @@ -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…
Cancel
Save