Browse Source

AP_HAL_AVR: AnalogIn returns new ADCSource each time a channel is requested

* fixes a bug where multiple sources created as pin -1, then change to
  appropriate pin on mavlink messages. Make treat each creation as distinct
  object.
master
Pat Hickey 12 years ago committed by Andrew Tridgell
parent
commit
087b1fa196
  1. 1
      libraries/AP_HAL_AVR/AnalogIn.h
  2. 11
      libraries/AP_HAL_AVR/AnalogIn_Common.cpp

1
libraries/AP_HAL_AVR/AnalogIn.h

@ -55,7 +55,6 @@ public: @@ -55,7 +55,6 @@ public:
AP_HAL::AnalogSource* channel(int16_t n, float prescale);
protected:
static ADCSource* _find_or_create_channel(int16_t num, float scale);
static ADCSource* _create_channel(int16_t num, float scale);
static void _register_channel(ADCSource*);
static void _timer_event(uint32_t);

11
libraries/AP_HAL_AVR/AnalogIn_Common.cpp

@ -31,15 +31,6 @@ void AVRAnalogIn::init(void* machtnichts) { @@ -31,15 +31,6 @@ void AVRAnalogIn::init(void* machtnichts) {
_register_channel(&_vcc);
}
ADCSource* AVRAnalogIn::_find_or_create_channel(int16_t pin, float scale) {
for(int16_t i = 0; i < _num_channels; i++) {
if (_channels[i]->_pin == pin) {
return _channels[i];
}
}
return _create_channel(pin, scale);
}
ADCSource* AVRAnalogIn::_create_channel(int16_t chnum, float scale) {
ADCSource *ch = new ADCSource(chnum, scale);
_register_channel(ch);
@ -121,7 +112,7 @@ AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch, float scale) { @@ -121,7 +112,7 @@ AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch, float scale) {
if (ch == ANALOG_INPUT_BOARD_VCC) {
return &_vcc;
} else {
return _find_or_create_channel(ch, scale);
return _create_channel(ch, scale);
}
}

Loading…
Cancel
Save