AP_HAL_Linux: Use from() method for downcast in Util class
This commit is contained in:
parent
cf6e6b7e82
commit
55e1d60b54
@ -24,7 +24,7 @@ LinuxGPIO_RPI::LinuxGPIO_RPI()
|
||||
|
||||
void LinuxGPIO_RPI::init()
|
||||
{
|
||||
int rpi_version = static_cast<LinuxUtilNavio*>(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);
|
||||
|
@ -392,7 +392,7 @@ LinuxRCInput_Navio::LinuxRCInput_Navio():
|
||||
last_signal(228),
|
||||
state(RCIN_NAVIO_INITIAL_STATE)
|
||||
{
|
||||
int version = static_cast<LinuxUtilNavio*>(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"
|
||||
|
@ -5,6 +5,11 @@
|
||||
class Linux::LinuxUtilNavio : public Linux::LinuxUtil {
|
||||
public:
|
||||
LinuxUtilNavio();
|
||||
|
||||
static LinuxUtilNavio *from(AP_HAL::Util *util) {
|
||||
return static_cast<LinuxUtilNavio*>(util);
|
||||
}
|
||||
|
||||
/* return the Raspberry Pi version */
|
||||
int get_rpi_version() const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user