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
This commit is contained in:
parent
0d26252bdb
commit
54c2c5f682
@ -9,6 +9,11 @@
|
||||
class Linux::LinuxRCInput : public AP_HAL::RCInput {
|
||||
public:
|
||||
LinuxRCInput();
|
||||
|
||||
static LinuxRCInput *from(AP_HAL::RCInput *rcinput) {
|
||||
return static_cast<LinuxRCInput*>(rcinput);
|
||||
}
|
||||
|
||||
virtual void init(void* machtnichts);
|
||||
bool new_input();
|
||||
uint8_t num_channels();
|
||||
|
@ -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<LinuxRCOutput_Bebop*>(rcout);
|
||||
}
|
||||
|
||||
void init(void* dummy);
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
|
@ -9,6 +9,11 @@
|
||||
class Linux::LinuxRPIOUARTDriver : public Linux::LinuxUARTDriver {
|
||||
public:
|
||||
LinuxRPIOUARTDriver();
|
||||
|
||||
static LinuxRPIOUARTDriver *from(AP_HAL::UARTDriver *uart) {
|
||||
return static_cast<LinuxRPIOUARTDriver*>(uart);
|
||||
}
|
||||
|
||||
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
||||
void _timer_tick(void);
|
||||
bool isExternal(void);
|
||||
|
@ -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();
|
||||
|
@ -16,13 +16,15 @@
|
||||
#define LINUX_STORAGE_LINE_SIZE (1<<LINUX_STORAGE_LINE_SHIFT)
|
||||
#define LINUX_STORAGE_NUM_LINES (LINUX_STORAGE_SIZE/LINUX_STORAGE_LINE_SIZE)
|
||||
|
||||
class Linux::LinuxStorage : public AP_HAL::Storage
|
||||
class Linux::LinuxStorage : public AP_HAL::Storage
|
||||
{
|
||||
public:
|
||||
LinuxStorage() :
|
||||
_fd(-1),
|
||||
_dirty_mask(0)
|
||||
{}
|
||||
LinuxStorage() : _fd(-1),_dirty_mask(0) { }
|
||||
|
||||
static LinuxStorage *from(AP_HAL::Storage *storage) {
|
||||
return static_cast<LinuxStorage*>(storage);
|
||||
}
|
||||
|
||||
void init(void* machtnichts) {}
|
||||
uint8_t read_byte(uint16_t loc);
|
||||
uint16_t read_word(uint16_t loc);
|
||||
|
@ -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<LinuxUARTDriver*>(uart);
|
||||
}
|
||||
|
||||
/* Linux implementations of UARTDriver virtual methods */
|
||||
void begin(uint32_t b);
|
||||
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
||||
|
@ -8,6 +8,10 @@
|
||||
|
||||
class Linux::LinuxUtil : public AP_HAL::Util {
|
||||
public:
|
||||
static LinuxUtil *from(AP_HAL::Util *util) {
|
||||
return static_cast<LinuxUtil*>(util);
|
||||
}
|
||||
|
||||
void init(int argc, char * const *argv) {
|
||||
saved_argc = argc;
|
||||
saved_argv = argv;
|
||||
|
Loading…
Reference in New Issue
Block a user