diff --git a/libraries/AP_HAL/AnalogIn.h b/libraries/AP_HAL/AnalogIn.h index 57b4947c03f576c7e0fde3622e2d790114be914c..fa9f291055a3137f74e0d22350e5e74cfae599aa 100644 --- a/libraries/AP_HAL/AnalogIn.h +++ b/libraries/AP_HAL/AnalogIn.h @@ -37,7 +37,6 @@ class AP_HAL::AnalogIn { public: virtual void init(void* implspecific) = 0; virtual AP_HAL::AnalogSource* channel(int16_t n) = 0; - virtual AP_HAL::AnalogSource* channel(int16_t n, float scale) = 0; }; #define ANALOG_INPUT_BOARD_VCC 254 diff --git a/libraries/AP_HAL_AVR/AnalogIn.h b/libraries/AP_HAL_AVR/AnalogIn.h index 16e5b4c6a697d4d04d5d68bd1a2a419f8085564b..f4456a8125632eb38ad882fa83a7ba3f64b4a7b2 100644 --- a/libraries/AP_HAL_AVR/AnalogIn.h +++ b/libraries/AP_HAL_AVR/AnalogIn.h @@ -12,7 +12,7 @@ public: friend class AP_HAL_AVR::AVRAnalogIn; /* pin designates the ADC input number, or when == AVR_ANALOG_PIN_VCC, * board vcc */ - ADCSource(uint8_t pin, float prescale = 1.0); + ADCSource(uint8_t pin); /* implement AnalogSource virtual api: */ float read_average(); @@ -58,9 +58,6 @@ private: uint8_t _stop_pin; uint16_t _settle_time_ms; uint32_t _read_start_time_ms; - - /* prescale scales the raw measurments for read()*/ - const float _prescale; }; /* AVRAnalogIn : a concrete class providing the implementations of the @@ -70,10 +67,9 @@ public: AVRAnalogIn(); void init(void* ap_hal_scheduler); AP_HAL::AnalogSource* channel(int16_t n); - AP_HAL::AnalogSource* channel(int16_t n, float prescale); protected: - static ADCSource* _create_channel(int16_t num, float scale); + static ADCSource* _create_channel(int16_t num); static void _register_channel(ADCSource*); static void _timer_event(uint32_t); static ADCSource* _channels[AVR_INPUT_MAX_CHANNELS]; diff --git a/libraries/AP_HAL_AVR/AnalogIn_ADC.cpp b/libraries/AP_HAL_AVR/AnalogIn_ADC.cpp index f72f140e1cfa06235819666a14e2786f857310d3..442dd98f87791beaae1d5287fc3a6e1b0cd410ee 100644 --- a/libraries/AP_HAL_AVR/AnalogIn_ADC.cpp +++ b/libraries/AP_HAL_AVR/AnalogIn_ADC.cpp @@ -11,14 +11,13 @@ using namespace AP_HAL_AVR; extern const AP_HAL::HAL& hal; -ADCSource::ADCSource(uint8_t pin, float prescale) : +ADCSource::ADCSource(uint8_t pin) : _pin(pin), _stop_pin(ANALOG_INPUT_NONE), _sum_count(0), _sum(0), _settle_time_ms(0), - _last_average(0), - _prescale(prescale) + _last_average(0) {} float ADCSource::read_average() { @@ -26,7 +25,7 @@ float ADCSource::read_average() { uint16_t v = (uint16_t) _read_average(); return 1126400UL / v; } else { - return _prescale * _read_average(); + return _read_average(); } } @@ -38,7 +37,7 @@ float ADCSource::read_latest() { if (_pin == ANALOG_INPUT_BOARD_VCC) { return 1126400UL / latest; } else { - return _prescale * latest; + return latest; } } diff --git a/libraries/AP_HAL_AVR/AnalogIn_Common.cpp b/libraries/AP_HAL_AVR/AnalogIn_Common.cpp index 1dc390d8ef5799b8ab19576a0aeeff0520d2f801..9f9cfdf5d598ff8a8eef38b2c5c7f2bfd0ae1e8e 100644 --- a/libraries/AP_HAL_AVR/AnalogIn_Common.cpp +++ b/libraries/AP_HAL_AVR/AnalogIn_Common.cpp @@ -33,8 +33,8 @@ void AVRAnalogIn::init(void* machtnichts) { _register_channel(&_vcc); } -ADCSource* AVRAnalogIn::_create_channel(int16_t chnum, float scale) { - ADCSource *ch = new ADCSource(chnum, scale); +ADCSource* AVRAnalogIn::_create_channel(int16_t chnum) { + ADCSource *ch = new ADCSource(chnum); _register_channel(ch); return ch; } @@ -110,14 +110,12 @@ next_channel: } -AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch) { - return this->channel(ch, 1.0); -} -AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch, float scale) { +AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch) +{ if (ch == ANALOG_INPUT_BOARD_VCC) { return &_vcc; } else { - return _create_channel(ch, scale); + return _create_channel(ch); } } diff --git a/libraries/AP_HAL_AVR_SITL/AnalogIn.cpp b/libraries/AP_HAL_AVR_SITL/AnalogIn.cpp index 958d788600a6c5605608a96641f1259386475b40..57d41725cfbf25655919fc969a0e55d8e922a582 100644 --- a/libraries/AP_HAL_AVR_SITL/AnalogIn.cpp +++ b/libraries/AP_HAL_AVR_SITL/AnalogIn.cpp @@ -11,10 +11,9 @@ using namespace AVR_SITL; extern const AP_HAL::HAL& hal; -ADCSource::ADCSource(SITL_State *sitlState, uint8_t pin, float prescale) : +ADCSource::ADCSource(SITL_State *sitlState, uint8_t pin) : _sitlState(sitlState), - _pin(pin), - _prescale(prescale) + _pin(pin) {} float ADCSource::read_average() { @@ -47,11 +46,7 @@ void SITLAnalogIn::init(void *ap_hal_scheduler) { } AP_HAL::AnalogSource* SITLAnalogIn::channel(int16_t pin) { - return channel(pin, 1.0); -} - -AP_HAL::AnalogSource* SITLAnalogIn::channel(int16_t pin, float prescale) { - return new ADCSource(_sitlState, pin, prescale); + return new ADCSource(_sitlState, pin); } #endif diff --git a/libraries/AP_HAL_AVR_SITL/AnalogIn.h b/libraries/AP_HAL_AVR_SITL/AnalogIn.h index 165745652a234f62ccbff5d47e5bc483127299ad..2a24b6ff81af39c969f4a0fccd00f214e4c5d9d3 100644 --- a/libraries/AP_HAL_AVR_SITL/AnalogIn.h +++ b/libraries/AP_HAL_AVR_SITL/AnalogIn.h @@ -12,7 +12,7 @@ public: friend class AVR_SITL::SITLAnalogIn; /* pin designates the ADC input number, or when == AVR_ANALOG_PIN_VCC, * board vcc */ - ADCSource(SITL_State *sitlState, uint8_t pin, float prescale = 1.0); + ADCSource(SITL_State *sitlState, uint8_t pin); /* implement AnalogSource virtual api: */ float read_average(); @@ -24,10 +24,8 @@ public: void set_settle_time(uint16_t settle_time_ms) {} private: - /* prescale scales the raw measurments for read()*/ SITL_State *_sitlState; uint8_t _pin; - const float _prescale; }; /* AVRAnalogIn : a concrete class providing the implementations of the @@ -39,7 +37,6 @@ public: } void init(void* ap_hal_scheduler); AP_HAL::AnalogSource* channel(int16_t n); - AP_HAL::AnalogSource* channel(int16_t n, float prescale); private: static ADCSource* _channels[SITL_INPUT_MAX_CHANNELS]; diff --git a/libraries/AP_HAL_Empty/AnalogIn.cpp b/libraries/AP_HAL_Empty/AnalogIn.cpp index a449b1bdd6f98647b2e72d093a2a1d366c54e182..f8d258064c465bca1a52807f87f053599502dae6 100644 --- a/libraries/AP_HAL_Empty/AnalogIn.cpp +++ b/libraries/AP_HAL_Empty/AnalogIn.cpp @@ -33,7 +33,4 @@ AP_HAL::AnalogSource* EmptyAnalogIn::channel(int16_t n) { return new EmptyAnalogSource(1.11); } -AP_HAL::AnalogSource* EmptyAnalogIn::channel(int16_t n, float scale) { - return new EmptyAnalogSource(scale/2); -} diff --git a/libraries/AP_HAL_Empty/AnalogIn.h b/libraries/AP_HAL_Empty/AnalogIn.h index b26e8209a7b2fbdbd74442253b440e5ffdf8e93d..460f06b8636f44454ead956e2f19d2bf1acfc820 100644 --- a/libraries/AP_HAL_Empty/AnalogIn.h +++ b/libraries/AP_HAL_Empty/AnalogIn.h @@ -23,6 +23,5 @@ public: EmptyAnalogIn(); void init(void* implspecific); AP_HAL::AnalogSource* channel(int16_t n); - AP_HAL::AnalogSource* channel(int16_t n, float scale); }; #endif // __AP_HAL_EMPTY_ANALOGIN_H__ diff --git a/libraries/AP_HAL_PX4/AnalogIn.cpp b/libraries/AP_HAL_PX4/AnalogIn.cpp index 8e2905440d77127907675f5d511c80e15766b761..2deda41890d99f329b624d7a8243afb541bd9a64 100644 --- a/libraries/AP_HAL_PX4/AnalogIn.cpp +++ b/libraries/AP_HAL_PX4/AnalogIn.cpp @@ -41,13 +41,12 @@ PX4AnalogSource* PX4AnalogIn::_channels[PX4_ANALOG_MAX_CHANNELS] = {}; int PX4AnalogIn::_battery_handle = -1; uint64_t PX4AnalogIn::_battery_timestamp; -PX4AnalogSource::PX4AnalogSource(int16_t pin, float initial_value, float scale) : +PX4AnalogSource::PX4AnalogSource(int16_t pin, float initial_value) : _pin(pin), _value(initial_value), _latest_value(initial_value), _sum_count(0), - _sum_value(0), - _scale(scale) + _sum_value(0) { } @@ -176,15 +175,10 @@ void PX4AnalogIn::_analogin_timer(uint32_t now) } AP_HAL::AnalogSource* PX4AnalogIn::channel(int16_t pin) -{ - return channel(pin, 1.0); -} - -AP_HAL::AnalogSource* PX4AnalogIn::channel(int16_t pin, float scale) { for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) { if (_channels[j] == NULL) { - _channels[j] = new PX4AnalogSource(pin, 0.0, scale); + _channels[j] = new PX4AnalogSource(pin, 0.0); return _channels[j]; } } diff --git a/libraries/AP_HAL_PX4/AnalogIn.h b/libraries/AP_HAL_PX4/AnalogIn.h index 11076c8d902b7f91b7e46e43f4c21f06840de794..e79c36487caa4e9157e4d79516b7fb8028db2e76 100644 --- a/libraries/AP_HAL_PX4/AnalogIn.h +++ b/libraries/AP_HAL_PX4/AnalogIn.h @@ -21,7 +21,7 @@ class PX4::PX4AnalogSource : public AP_HAL::AnalogSource { public: friend class PX4::PX4AnalogIn; - PX4AnalogSource(int16_t pin, float initial_value, float scale); + PX4AnalogSource(int16_t pin, float initial_value); float read_average(); float read_latest(); void set_pin(uint8_t p); @@ -41,7 +41,6 @@ private: float _latest_value; uint8_t _sum_count; float _sum_value; - float _scale; void _add_value(float v); }; @@ -50,7 +49,6 @@ public: PX4AnalogIn(); void init(void* implspecific); AP_HAL::AnalogSource* channel(int16_t pin); - AP_HAL::AnalogSource* channel(int16_t pin, float scale); private: static int _adc_fd; diff --git a/libraries/AP_HAL_SMACCM/AnalogIn.cpp b/libraries/AP_HAL_SMACCM/AnalogIn.cpp index f52cdf8539e13bbc36c7577dfac68bd6185578d2..b7f172de752c69ad9321eda7af070ece683e7a70 100644 --- a/libraries/AP_HAL_SMACCM/AnalogIn.cpp +++ b/libraries/AP_HAL_SMACCM/AnalogIn.cpp @@ -34,7 +34,3 @@ AP_HAL::AnalogSource* SMACCMAnalogIn::channel(int16_t n) { return new SMACCMAnalogSource(1.11); } -AP_HAL::AnalogSource* SMACCMAnalogIn::channel(int16_t n, float scale) { - return new SMACCMAnalogSource(scale/2); -} - diff --git a/libraries/AP_HAL_SMACCM/AnalogIn.h b/libraries/AP_HAL_SMACCM/AnalogIn.h index 7b98a2fa054eeaeca75d98f24e767d26445fb9e5..6e6cb6d267a6b9a2a33f389b1c03d99acbfd98b9 100644 --- a/libraries/AP_HAL_SMACCM/AnalogIn.h +++ b/libraries/AP_HAL_SMACCM/AnalogIn.h @@ -24,6 +24,5 @@ public: SMACCMAnalogIn(); void init(void* implspecific); AP_HAL::AnalogSource* channel(int16_t n); - AP_HAL::AnalogSource* channel(int16_t n, float scale); }; #endif // __AP_HAL_SMACCM_ANALOGIN_H__