AP_AnalogSource: added set_pin() interface
this allows pin numbers to be changed at runtime
This commit is contained in:
parent
5642922ca7
commit
a979fb6014
@ -131,17 +131,9 @@ float AP_AnalogSource_Arduino::read(void)
|
||||
}
|
||||
|
||||
|
||||
// assign a slot in the pins_watched
|
||||
void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
|
||||
// remap pin numbers to physical pin
|
||||
uint8_t AP_AnalogSource_Arduino::_remap_pin(uint8_t pin)
|
||||
{
|
||||
// ensure we don't try to read from too many analog pins
|
||||
if (num_pins_watched == MAX_PIN_SOURCES) {
|
||||
while (true) {
|
||||
Serial.printf_P(PSTR("MAX_PIN_SOURCES REACHED\n"));
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
if (pin != ANALOG_PIN_VCC) {
|
||||
// allow pin to be a channel (i.e. "A0") or an actual pin
|
||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
@ -154,7 +146,21 @@ void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
|
||||
if (pin >= 14) pin -= 14;
|
||||
#endif
|
||||
}
|
||||
return pin;
|
||||
}
|
||||
|
||||
// assign a slot in the pins_watched
|
||||
void AP_AnalogSource_Arduino::_assign_pin_index(uint8_t pin)
|
||||
{
|
||||
// ensure we don't try to read from too many analog pins
|
||||
if (num_pins_watched == MAX_PIN_SOURCES) {
|
||||
while (true) {
|
||||
Serial.printf_P(PSTR("MAX_PIN_SOURCES REACHED\n"));
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
pin = _remap_pin(pin);
|
||||
_pin_index = num_pins_watched;
|
||||
pins[_pin_index].pin = pin;
|
||||
num_pins_watched++;
|
||||
@ -164,3 +170,16 @@ void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
|
||||
ADCSRA |= _BV(ADEN);
|
||||
}
|
||||
}
|
||||
|
||||
// change which pin to read
|
||||
void AP_AnalogSource_Arduino::set_pin(uint8_t pin)
|
||||
{
|
||||
pin = _remap_pin(pin);
|
||||
if (pins[_pin_index].pin != pin) {
|
||||
cli();
|
||||
pins[_pin_index].pin = pin;
|
||||
pins[_pin_index].sum = 0;
|
||||
pins[_pin_index].sum_count = 0;
|
||||
sei();
|
||||
}
|
||||
}
|
||||
|
@ -15,7 +15,7 @@ class AP_AnalogSource_Arduino : public AP_AnalogSource
|
||||
public:
|
||||
AP_AnalogSource_Arduino( uint8_t pin, float prescale = 1.0 ) :
|
||||
_prescale(prescale) {
|
||||
assign_pin_index(pin);
|
||||
_assign_pin_index(pin);
|
||||
}
|
||||
|
||||
// setup the timer callback
|
||||
@ -34,11 +34,16 @@ public:
|
||||
// we last called read_average().
|
||||
float read_average(void);
|
||||
|
||||
// set the pin to be used for this source. This allows for the pin
|
||||
// to be changed at runtime
|
||||
void set_pin(uint8_t pin);
|
||||
|
||||
private:
|
||||
uint8_t _pin_index;
|
||||
float _prescale;
|
||||
|
||||
void assign_pin_index(uint8_t pin);
|
||||
uint8_t _remap_pin(uint8_t pin);
|
||||
void _assign_pin_index(uint8_t pin);
|
||||
};
|
||||
|
||||
#endif // __AP_ANALOG_SOURCE_ARDUINO_H__
|
||||
|
Loading…
Reference in New Issue
Block a user