From 5b2b4430b3c82b428b2339054e6b1613f17c2c33 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Mon, 9 Jan 2017 13:22:43 +0100 Subject: [PATCH] AP_HAL_SITL: AnalogIn minor fixes change pin to int16_t to match real implementation and prevent casting. make constructor explicit --- libraries/AP_HAL_SITL/AnalogIn.cpp | 2 +- libraries/AP_HAL_SITL/AnalogIn.h | 8 +++----- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_SITL/AnalogIn.cpp b/libraries/AP_HAL_SITL/AnalogIn.cpp index 957c27fdba..920851a41b 100644 --- a/libraries/AP_HAL_SITL/AnalogIn.cpp +++ b/libraries/AP_HAL_SITL/AnalogIn.cpp @@ -9,7 +9,7 @@ using namespace HALSITL; extern const AP_HAL::HAL& hal; -ADCSource::ADCSource(SITL_State *sitlState, uint8_t pin) : +ADCSource::ADCSource(SITL_State *sitlState, int16_t pin) : _sitlState(sitlState), _pin(pin) {} diff --git a/libraries/AP_HAL_SITL/AnalogIn.h b/libraries/AP_HAL_SITL/AnalogIn.h index 936fcea1d6..c05d8d90e6 100644 --- a/libraries/AP_HAL_SITL/AnalogIn.h +++ b/libraries/AP_HAL_SITL/AnalogIn.h @@ -9,7 +9,7 @@ class HALSITL::ADCSource : public AP_HAL::AnalogSource { public: friend class HALSITL::AnalogIn; /* pin designates the ADC input number */ - ADCSource(SITL_State *sitlState, uint8_t pin); + ADCSource(SITL_State *sitlState, int16_t pin); /* implement AnalogSource virtual api: */ float read_average(); @@ -25,16 +25,14 @@ public: private: SITL_State *_sitlState; - uint8_t _pin; + int16_t _pin; }; /* AnalogIn : a concrete class providing the implementations of the * timer event and the AP_HAL::AnalogIn interface */ class HALSITL::AnalogIn : public AP_HAL::AnalogIn { public: - AnalogIn(SITL_State *sitlState) { - _sitlState = sitlState; - } + explicit AnalogIn(SITL_State *sitlState): _sitlState(sitlState) {} void init(); AP_HAL::AnalogSource* channel(int16_t n); float board_voltage(void) {