From 7f5b32f59f0c0593620883085eb6791857ea36e8 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Mon, 9 Jan 2017 13:25:29 +0100 Subject: [PATCH] AP_HAL_SITL: GPIO minor fixes fix style make constructor explicit fix implicit cast for unsigned to signed value correct DigitalSource constructor definition --- libraries/AP_HAL_SITL/GPIO.cpp | 38 +++++++++++++++++++--------------- libraries/AP_HAL_SITL/GPIO.h | 30 +++++++++++++-------------- 2 files changed, 35 insertions(+), 33 deletions(-) diff --git a/libraries/AP_HAL_SITL/GPIO.cpp b/libraries/AP_HAL_SITL/GPIO.cpp index ff54ceb350..6de3a401bd 100644 --- a/libraries/AP_HAL_SITL/GPIO.cpp +++ b/libraries/AP_HAL_SITL/GPIO.cpp @@ -13,33 +13,32 @@ void GPIO::pinMode(uint8_t pin, uint8_t output) int8_t GPIO::analogPinToDigitalPin(uint8_t pin) { - return pin; + return pin; } - uint8_t GPIO::read(uint8_t pin) { - if (!sitlState->_sitl) { + if (!_sitlState->_sitl) { return 0; } - uint8_t mask = sitlState->_sitl->pin_mask.get(); - return mask & (1U<(_sitlState->_sitl->pin_mask.get()); + return static_cast((mask & (1U << pin)) ? 1 : 0); } void GPIO::write(uint8_t pin, uint8_t value) { - if (!sitlState->_sitl) { + if (!_sitlState->_sitl) { return; } - uint8_t mask = sitlState->_sitl->pin_mask.get(); + uint8_t mask = static_cast(_sitlState->_sitl->pin_mask.get()); uint8_t new_mask = mask; if (value) { - new_mask |= (1U<_sitl->pin_mask.set_and_notify(new_mask); + _sitlState->_sitl->pin_mask.set_and_notify(new_mask); } } @@ -50,7 +49,12 @@ void GPIO::toggle(uint8_t pin) /* Alternative interface: */ AP_HAL::DigitalSource* GPIO::channel(uint16_t n) { - return new DigitalSource(0); + if (n < 8) { // (ie. sizeof(pin_mask)*8) + return new DigitalSource(static_cast(n)); + } else { + return nullptr; + } + } /* Interrupt interface: */ @@ -64,8 +68,8 @@ bool GPIO::usb_connected(void) return false; } -DigitalSource::DigitalSource(uint8_t v) : - pin(v) +DigitalSource::DigitalSource(uint8_t pin) : + _pin(pin) {} void DigitalSource::mode(uint8_t output) @@ -73,16 +77,16 @@ void DigitalSource::mode(uint8_t output) uint8_t DigitalSource::read() { - return hal.gpio->read(pin); + return hal.gpio->read(_pin); } void DigitalSource::write(uint8_t value) { - value = value?1:0; - return hal.gpio->write(pin, value); + value = static_cast(value ? 1 : 0); + return hal.gpio->write(_pin, value); } void DigitalSource::toggle() { - return hal.gpio->write(pin, !hal.gpio->read(pin)); + return hal.gpio->write(_pin, !hal.gpio->read(_pin)); } diff --git a/libraries/AP_HAL_SITL/GPIO.h b/libraries/AP_HAL_SITL/GPIO.h index d31f443799..7c36ccf502 100644 --- a/libraries/AP_HAL_SITL/GPIO.h +++ b/libraries/AP_HAL_SITL/GPIO.h @@ -4,38 +4,36 @@ class HALSITL::GPIO : public AP_HAL::GPIO { public: - GPIO(SITL_State *_sitlState) { - sitlState = _sitlState; - } - void init(); - void pinMode(uint8_t pin, uint8_t output); - int8_t analogPinToDigitalPin(uint8_t pin); + explicit GPIO(SITL_State *sitlState): _sitlState(sitlState) {} + void init(); + void pinMode(uint8_t pin, uint8_t output); + int8_t analogPinToDigitalPin(uint8_t pin); uint8_t read(uint8_t pin); - void write(uint8_t pin, uint8_t value); - void toggle(uint8_t pin); + void write(uint8_t pin, uint8_t value); + void toggle(uint8_t pin); /* Alternative interface: */ AP_HAL::DigitalSource* channel(uint16_t n); /* Interrupt interface: */ - bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, + bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode); /* return true if USB cable is connected */ - bool usb_connected(void); + bool usb_connected(void); private: - SITL_State *sitlState; + SITL_State *_sitlState; }; class HALSITL::DigitalSource : public AP_HAL::DigitalSource { public: - DigitalSource(uint8_t _pin); - void mode(uint8_t output); + explicit DigitalSource(uint8_t pin); + void mode(uint8_t output); uint8_t read(); - void write(uint8_t value); - void toggle(); + void write(uint8_t value); + void toggle(); private: - uint8_t pin; + uint8_t _pin; };