mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_AVR: analog input fixed when ANALOG_INPUT_NONE
* need to provide new sample so we dont spin forever
This commit is contained in:
parent
2826a605ba
commit
765e2da8a7
|
@ -70,6 +70,7 @@ void AVRAnalogIn::_register_channel(ADCSource* ch) {
|
||||||
void AVRAnalogIn::_timer_event(uint32_t t) {
|
void AVRAnalogIn::_timer_event(uint32_t t) {
|
||||||
|
|
||||||
if (_channels[_active_channel]->_pin == ANALOG_INPUT_NONE) {
|
if (_channels[_active_channel]->_pin == ANALOG_INPUT_NONE) {
|
||||||
|
_channels[_active_channel]->new_sample(0);
|
||||||
goto next_channel;
|
goto next_channel;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue