AP_HAL_Linux: fix build for raspilot after Util change

Make sure raspilot also builds after making the Util class common for
RPI-based boards.
This commit is contained in:
Lucas De Marchi 2015-09-23 22:53:42 -03:00 committed by Andrew Tridgell
parent 55e1d60b54
commit fc2a1d27b4
7 changed files with 16 additions and 16 deletions

View File

@ -38,7 +38,7 @@ namespace Linux {
class LinuxSemaphore;
class LinuxScheduler;
class LinuxUtil;
class LinuxUtilNavio;
class LinuxUtilRPI;
class ToneAlarm; //limit the scope of ToneAlarm driver to Linux_HAL only
}

View File

@ -31,7 +31,7 @@
#include "Scheduler.h"
#include "ToneAlarmDriver.h"
#include "Util.h"
#include "Util_Navio.h"
#include "Util_RPI.h"
#endif // __AP_HAL_LINUX_PRIVATE_H__

View File

@ -3,7 +3,7 @@
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
#include "GPIO.h"
#include "Util_Navio.h"
#include "Util_RPI.h"
#include <stdio.h>
#include <stdlib.h>
@ -24,7 +24,7 @@ LinuxGPIO_RPI::LinuxGPIO_RPI()
void LinuxGPIO_RPI::init()
{
int rpi_version = LinuxUtilNavio::from(hal.util)->get_rpi_version();
int rpi_version = LinuxUtilRPI::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);

View File

@ -120,7 +120,7 @@ static Empty::EmptyRCOutput rcoutDriver;
static LinuxScheduler schedulerInstance;
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
static LinuxUtilNavio utilInstance;
static LinuxUtilRPI utilInstance;
#else
static LinuxUtil utilInstance;
#endif

View File

@ -3,7 +3,7 @@
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
#include "GPIO.h"
#include "RCInput_Navio.h"
#include "Util_Navio.h"
#include "Util_RPI.h"
#include <stdio.h>
#include <stdlib.h>
@ -392,7 +392,7 @@ LinuxRCInput_Navio::LinuxRCInput_Navio():
last_signal(228),
state(RCIN_NAVIO_INITIAL_STATE)
{
int version = LinuxUtilNavio::from(hal.util)->get_rpi_version();
int version = LinuxUtilRPI::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"

View File

@ -1,6 +1,6 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
#include <stdio.h>
#include <stdarg.h>
@ -10,19 +10,19 @@
#include <errno.h>
#include <time.h>
#include "Util_Navio.h"
#include "Util_RPI.h"
extern const AP_HAL::HAL& hal;
using namespace Linux;
LinuxUtilNavio::LinuxUtilNavio()
LinuxUtilRPI::LinuxUtilRPI()
{
_check_rpi_version();
}
#define MAX_SIZE_LINE 50
int LinuxUtilNavio::_check_rpi_version()
int LinuxUtilRPI::_check_rpi_version()
{
char buffer[MAX_SIZE_LINE];
const char* hardware_description_entry = "Hardware";
@ -61,7 +61,7 @@ int LinuxUtilNavio::_check_rpi_version()
return _rpi_version;
}
int LinuxUtilNavio::get_rpi_version() const
int LinuxUtilRPI::get_rpi_version() const
{
return _rpi_version;
}

View File

@ -2,12 +2,12 @@
#include "Util.h"
class Linux::LinuxUtilNavio : public Linux::LinuxUtil {
class Linux::LinuxUtilRPI : public Linux::LinuxUtil {
public:
LinuxUtilNavio();
LinuxUtilRPI();
static LinuxUtilNavio *from(AP_HAL::Util *util) {
return static_cast<LinuxUtilNavio*>(util);
static LinuxUtilRPI *from(AP_HAL::Util *util) {
return static_cast<LinuxUtilRPI*>(util);
}
/* return the Raspberry Pi version */