From 54c2c5f6824e5e6dedae3b0b1b87a85bdaff9a36 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Sun, 13 Sep 2015 15:28:02 -0300 Subject: [PATCH] AP_HAL_Linux: use method for downcast Instead of just doing a static cast to the desired class, use a method named "from". Pros: - When we have data shared on the parent class, the code is cleaner in child class when it needs to access this data. Almost all the data we use in AP_HAL benefits from this - There's a minimal type checking because now we are using a method that can only receive the type of the parent class --- libraries/AP_HAL_Linux/RCInput.h | 5 +++++ libraries/AP_HAL_Linux/RCOutput_Bebop.h | 5 +++++ libraries/AP_HAL_Linux/RPIOUARTDriver.h | 5 +++++ libraries/AP_HAL_Linux/Scheduler.cpp | 19 +++++++++---------- libraries/AP_HAL_Linux/Storage.h | 12 +++++++----- libraries/AP_HAL_Linux/UARTDriver.h | 5 +++++ libraries/AP_HAL_Linux/Util.h | 4 ++++ 7 files changed, 40 insertions(+), 15 deletions(-) diff --git a/libraries/AP_HAL_Linux/RCInput.h b/libraries/AP_HAL_Linux/RCInput.h index ce2a78a395..5a3c2fda2a 100644 --- a/libraries/AP_HAL_Linux/RCInput.h +++ b/libraries/AP_HAL_Linux/RCInput.h @@ -9,6 +9,11 @@ class Linux::LinuxRCInput : public AP_HAL::RCInput { public: LinuxRCInput(); + + static LinuxRCInput *from(AP_HAL::RCInput *rcinput) { + return static_cast(rcinput); + } + virtual void init(void* machtnichts); bool new_input(); uint8_t num_channels(); diff --git a/libraries/AP_HAL_Linux/RCOutput_Bebop.h b/libraries/AP_HAL_Linux/RCOutput_Bebop.h index 43e0ac6889..1c39a95f67 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Bebop.h +++ b/libraries/AP_HAL_Linux/RCOutput_Bebop.h @@ -50,6 +50,11 @@ public: class Linux::LinuxRCOutput_Bebop : public AP_HAL::RCOutput { public: LinuxRCOutput_Bebop(); + + static LinuxRCOutput_Bebop *from(AP_HAL::RCOutput *rcout) { + return static_cast(rcout); + } + void init(void* dummy); void set_freq(uint32_t chmask, uint16_t freq_hz); uint16_t get_freq(uint8_t ch); diff --git a/libraries/AP_HAL_Linux/RPIOUARTDriver.h b/libraries/AP_HAL_Linux/RPIOUARTDriver.h index 22d9fc61fe..bd5e253dee 100644 --- a/libraries/AP_HAL_Linux/RPIOUARTDriver.h +++ b/libraries/AP_HAL_Linux/RPIOUARTDriver.h @@ -9,6 +9,11 @@ class Linux::LinuxRPIOUARTDriver : public Linux::LinuxUARTDriver { public: LinuxRPIOUARTDriver(); + + static LinuxRPIOUARTDriver *from(AP_HAL::UARTDriver *uart) { + return static_cast(uart); + } + void begin(uint32_t b, uint16_t rxS, uint16_t txS); void _timer_tick(void); bool isExternal(void); diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index 9313cf51fc..300a8d3b65 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -341,7 +341,7 @@ void *LinuxScheduler::_rcin_thread(void *arg) } while (true) { sched->_microsleep(APM_LINUX_RCIN_PERIOD); - ((LinuxRCInput *)hal.rcin)->_timer_tick(); + LinuxRCInput::from(hal.rcin)->_timer_tick(); } return NULL; } @@ -357,18 +357,17 @@ void *LinuxScheduler::_uart_thread(void* arg) sched->_microsleep(APM_LINUX_UART_PERIOD); // process any pending serial bytes - ((LinuxUARTDriver *)hal.uartA)->_timer_tick(); - ((LinuxUARTDriver *)hal.uartB)->_timer_tick(); + LinuxUARTDriver::from(hal.uartA)->_timer_tick(); + LinuxUARTDriver::from(hal.uartB)->_timer_tick(); #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT //SPI UART not use SPI - if ( ((LinuxRPIOUARTDriver *)hal.uartC)->isExternal() ) - { - ((LinuxRPIOUARTDriver *)hal.uartC)->_timer_tick(); + if (LinuxRPIOUARTDriver::from(hal.uartC)->isExternal()) { + LinuxRPIOUARTDriver::from(hal.uartC)->_timer_tick(); } #else - ((LinuxUARTDriver *)hal.uartC)->_timer_tick(); + LinuxUARTDriver::from(hal.uartC)->_timer_tick(); #endif - ((LinuxUARTDriver *)hal.uartE)->_timer_tick(); + LinuxUARTDriver::from(hal.uartE)->_timer_tick(); } return NULL; } @@ -384,7 +383,7 @@ void *LinuxScheduler::_tonealarm_thread(void* arg) sched->_microsleep(APM_LINUX_TONEALARM_PERIOD); // process tone command - ((LinuxUtil *)hal.util)->_toneAlarm_timer_tick(); + LinuxUtil::from(hal.util)->_toneAlarm_timer_tick(); } return NULL; } @@ -400,7 +399,7 @@ void *LinuxScheduler::_io_thread(void* arg) sched->_microsleep(APM_LINUX_IO_PERIOD); // process any pending storage writes - ((LinuxStorage *)hal.storage)->_timer_tick(); + LinuxStorage::from(hal.storage)->_timer_tick(); // run registered IO procepsses sched->_run_io(); diff --git a/libraries/AP_HAL_Linux/Storage.h b/libraries/AP_HAL_Linux/Storage.h index 18cb476f09..51e02ec525 100644 --- a/libraries/AP_HAL_Linux/Storage.h +++ b/libraries/AP_HAL_Linux/Storage.h @@ -16,13 +16,15 @@ #define LINUX_STORAGE_LINE_SIZE (1<(storage); + } + void init(void* machtnichts) {} uint8_t read_byte(uint16_t loc); uint16_t read_word(uint16_t loc); diff --git a/libraries/AP_HAL_Linux/UARTDriver.h b/libraries/AP_HAL_Linux/UARTDriver.h index a6411a9e8c..d5036dc01b 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.h +++ b/libraries/AP_HAL_Linux/UARTDriver.h @@ -9,6 +9,11 @@ class Linux::LinuxUARTDriver : public AP_HAL::UARTDriver { public: LinuxUARTDriver(bool default_console); + + static LinuxUARTDriver *from(AP_HAL::UARTDriver *uart) { + return static_cast(uart); + } + /* Linux implementations of UARTDriver virtual methods */ void begin(uint32_t b); void begin(uint32_t b, uint16_t rxS, uint16_t txS); diff --git a/libraries/AP_HAL_Linux/Util.h b/libraries/AP_HAL_Linux/Util.h index 505cd6099d..fb88f1d1fe 100644 --- a/libraries/AP_HAL_Linux/Util.h +++ b/libraries/AP_HAL_Linux/Util.h @@ -8,6 +8,10 @@ class Linux::LinuxUtil : public AP_HAL::Util { public: + static LinuxUtil *from(AP_HAL::Util *util) { + return static_cast(util); + } + void init(int argc, char * const *argv) { saved_argc = argc; saved_argv = argv;