diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.cpp b/libraries/AP_HAL_Linux/GPIO_RPI.cpp index c861e877ac..de7f945260 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.cpp +++ b/libraries/AP_HAL_Linux/GPIO_RPI.cpp @@ -24,7 +24,7 @@ LinuxGPIO_RPI::LinuxGPIO_RPI() void LinuxGPIO_RPI::init() { - int rpi_version = static_cast(hal.util)->get_rpi_version(); + int rpi_version = LinuxUtilNavio::from(hal.util)->get_rpi_version(); uint32_t gpio_address = rpi_version == 1 ? GPIO_BASE(BCM2708_PERI_BASE) : GPIO_BASE(BCM2709_PERI_BASE); uint32_t pwm_address = rpi_version == 1 ? PWM_BASE(BCM2708_PERI_BASE) : PWM_BASE(BCM2709_PERI_BASE); uint32_t clk_address = rpi_version == 1 ? CLOCK_BASE(BCM2708_PERI_BASE) : CLOCK_BASE(BCM2709_PERI_BASE); diff --git a/libraries/AP_HAL_Linux/RCInput_Navio.cpp b/libraries/AP_HAL_Linux/RCInput_Navio.cpp index efd97dbc06..fd037618a8 100644 --- a/libraries/AP_HAL_Linux/RCInput_Navio.cpp +++ b/libraries/AP_HAL_Linux/RCInput_Navio.cpp @@ -392,7 +392,7 @@ LinuxRCInput_Navio::LinuxRCInput_Navio(): last_signal(228), state(RCIN_NAVIO_INITIAL_STATE) { - int version = static_cast(hal.util)->get_rpi_version(); + int version = LinuxUtilNavio::from(hal.util)->get_rpi_version(); set_physical_addresses(version); //Init memory for buffer and for DMA control blocks. See comments in "init_ctrl_data()" to understand values "2" and "113" diff --git a/libraries/AP_HAL_Linux/Util_Navio.h b/libraries/AP_HAL_Linux/Util_Navio.h index a64304ad9c..7217102dcd 100644 --- a/libraries/AP_HAL_Linux/Util_Navio.h +++ b/libraries/AP_HAL_Linux/Util_Navio.h @@ -5,6 +5,11 @@ class Linux::LinuxUtilNavio : public Linux::LinuxUtil { public: LinuxUtilNavio(); + + static LinuxUtilNavio *from(AP_HAL::Util *util) { + return static_cast(util); + } + /* return the Raspberry Pi version */ int get_rpi_version() const;