From a5b20b4dfcaca1178c92af08021c8d01325fd01c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell <tridge@samba.org> Date: Mon, 13 May 2013 15:29:42 +1000 Subject: [PATCH] AP_HAL: removed scaling factor on analog sources these are not use anymore, as voltage_average() is used instead --- libraries/AP_HAL/AnalogIn.h | 1 - libraries/AP_HAL_AVR/AnalogIn.h | 8 ++------ libraries/AP_HAL_AVR/AnalogIn_ADC.cpp | 9 ++++----- libraries/AP_HAL_AVR/AnalogIn_Common.cpp | 12 +++++------- libraries/AP_HAL_AVR_SITL/AnalogIn.cpp | 11 +++-------- libraries/AP_HAL_AVR_SITL/AnalogIn.h | 5 +---- libraries/AP_HAL_Empty/AnalogIn.cpp | 3 --- libraries/AP_HAL_Empty/AnalogIn.h | 1 - libraries/AP_HAL_PX4/AnalogIn.cpp | 12 +++--------- libraries/AP_HAL_PX4/AnalogIn.h | 4 +--- libraries/AP_HAL_SMACCM/AnalogIn.cpp | 4 ---- libraries/AP_HAL_SMACCM/AnalogIn.h | 1 - 12 files changed, 19 insertions(+), 52 deletions(-) diff --git a/libraries/AP_HAL/AnalogIn.h b/libraries/AP_HAL/AnalogIn.h index 57b4947c0..fa9f29105 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 16e5b4c6a..f4456a812 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 f72f140e1..442dd98f8 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 1dc390d8e..9f9cfdf5d 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 958d78860..57d41725c 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 165745652..2a24b6ff8 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 a449b1bdd..f8d258064 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 b26e8209a..460f06b86 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 8e2905440..2deda4189 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 11076c8d9..e79c36487 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 f52cdf853..b7f172de7 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 7b98a2fa0..6e6cb6d26 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__ -- GitLab