AP_HAL_Linux: Move RPi version check to util class
- Moved the version check functions to util. - Removed a redundant version check. - Removed redundant version check functions from RCInput.
This commit is contained in:
parent
2590db378a
commit
15b3717d89
@ -38,6 +38,7 @@ namespace Linux {
|
|||||||
class LinuxSemaphore;
|
class LinuxSemaphore;
|
||||||
class LinuxScheduler;
|
class LinuxScheduler;
|
||||||
class LinuxUtil;
|
class LinuxUtil;
|
||||||
|
class LinuxUtilNavio;
|
||||||
class ToneAlarm; //limit the scope of ToneAlarm driver to Linux_HAL only
|
class ToneAlarm; //limit the scope of ToneAlarm driver to Linux_HAL only
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -31,6 +31,7 @@
|
|||||||
#include "Scheduler.h"
|
#include "Scheduler.h"
|
||||||
#include "ToneAlarmDriver.h"
|
#include "ToneAlarmDriver.h"
|
||||||
#include "Util.h"
|
#include "Util.h"
|
||||||
|
#include "Util_Navio.h"
|
||||||
|
|
||||||
#endif // __AP_HAL_LINUX_PRIVATE_H__
|
#endif // __AP_HAL_LINUX_PRIVATE_H__
|
||||||
|
|
||||||
|
@ -3,6 +3,8 @@
|
|||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||||
|
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
#include "Util_Navio.h"
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
@ -13,7 +15,6 @@
|
|||||||
#include <sys/mman.h>
|
#include <sys/mman.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
|
|
||||||
#define MAX_SIZE_LINE 50
|
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
@ -21,42 +22,9 @@ static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
|||||||
LinuxGPIO_RPI::LinuxGPIO_RPI()
|
LinuxGPIO_RPI::LinuxGPIO_RPI()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
int LinuxGPIO_RPI::getRaspberryPiVersion() const
|
|
||||||
{
|
|
||||||
char buffer[MAX_SIZE_LINE];
|
|
||||||
const char* hardware_description_entry = "Hardware";
|
|
||||||
const char* v1 = "BCM2708";
|
|
||||||
const char* v2 = "BCM2709";
|
|
||||||
char* flag;
|
|
||||||
FILE* fd;
|
|
||||||
|
|
||||||
fd = fopen("/proc/cpuinfo", "r");
|
|
||||||
|
|
||||||
while (fgets(buffer, MAX_SIZE_LINE, fd) != NULL) {
|
|
||||||
flag = strstr(buffer, hardware_description_entry);
|
|
||||||
|
|
||||||
if (flag != NULL) {
|
|
||||||
if (strstr(buffer, v2) != NULL) {
|
|
||||||
printf("Raspberry Pi 2 with BCM2709!\n");
|
|
||||||
fclose(fd);
|
|
||||||
return 2;
|
|
||||||
} else if (strstr(buffer, v1) != NULL) {
|
|
||||||
printf("Raspberry Pi 1 with BCM2708!\n");
|
|
||||||
fclose(fd);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* defaults to 1 */
|
|
||||||
fprintf(stderr, "Could not detect RPi version, defaulting to 1\n");
|
|
||||||
fclose(fd);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
void LinuxGPIO_RPI::init()
|
void LinuxGPIO_RPI::init()
|
||||||
{
|
{
|
||||||
int rpi_version = getRaspberryPiVersion();
|
int rpi_version = static_cast<LinuxUtilNavio*>(hal.util)->get_rpi_version();
|
||||||
uint32_t gpio_address = rpi_version == 1 ? GPIO_BASE(BCM2708_PERI_BASE) : GPIO_BASE(BCM2709_PERI_BASE);
|
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 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);
|
uint32_t clk_address = rpi_version == 1 ? CLOCK_BASE(BCM2708_PERI_BASE) : CLOCK_BASE(BCM2709_PERI_BASE);
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
|
|
||||||
#ifndef __AP_HAL_LINUX_GPIO_RPI_H__
|
#ifndef __AP_HAL_LINUX_GPIO_RPI_H__
|
||||||
#define __AP_HAL_LINUX_GPIO_RPI_H__
|
#define __AP_HAL_LINUX_GPIO_RPI_H__
|
||||||
|
|
||||||
@ -74,7 +73,6 @@ private:
|
|||||||
volatile uint32_t *gpio;
|
volatile uint32_t *gpio;
|
||||||
volatile uint32_t *pwm;
|
volatile uint32_t *pwm;
|
||||||
volatile uint32_t *clk;
|
volatile uint32_t *clk;
|
||||||
int getRaspberryPiVersion() const;
|
|
||||||
void setPWM0Period(uint32_t time_us);
|
void setPWM0Period(uint32_t time_us);
|
||||||
void setPWM0Duty(uint8_t percent);
|
void setPWM0Duty(uint8_t percent);
|
||||||
|
|
||||||
|
@ -119,7 +119,11 @@ static Empty::EmptyRCOutput rcoutDriver;
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
static LinuxScheduler schedulerInstance;
|
static LinuxScheduler schedulerInstance;
|
||||||
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||||
|
static LinuxUtilNavio utilInstance;
|
||||||
|
#else
|
||||||
static LinuxUtil utilInstance;
|
static LinuxUtil utilInstance;
|
||||||
|
#endif
|
||||||
|
|
||||||
HAL_Linux::HAL_Linux() :
|
HAL_Linux::HAL_Linux() :
|
||||||
AP_HAL::HAL(
|
AP_HAL::HAL(
|
||||||
|
@ -2,6 +2,9 @@
|
|||||||
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
#include "RCInput_Navio.h"
|
||||||
|
#include "Util_Navio.h"
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
@ -18,7 +21,7 @@
|
|||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
#include <sys/mman.h>
|
#include <sys/mman.h>
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include "RCInput_Navio.h"
|
|
||||||
|
|
||||||
//Parametres
|
//Parametres
|
||||||
#define RCIN_NAVIO_BUFFER_LENGTH 8
|
#define RCIN_NAVIO_BUFFER_LENGTH 8
|
||||||
@ -188,37 +191,6 @@ uint32_t Memory_table::get_page_count() const
|
|||||||
return _page_count;
|
return _page_count;
|
||||||
}
|
}
|
||||||
|
|
||||||
// More memory mapping
|
|
||||||
int get_raspberry_pi_version()
|
|
||||||
{
|
|
||||||
char buffer[RCIN_NAVIO_MAX_SIZE_LINE];
|
|
||||||
const char* hardware_description_entry = "Hardware";
|
|
||||||
const char* v1 = "BCM2708";
|
|
||||||
const char* v2 = "BCM2709";
|
|
||||||
char* flag;
|
|
||||||
FILE* fd;
|
|
||||||
|
|
||||||
fd = fopen("/proc/cpuinfo", "r");
|
|
||||||
|
|
||||||
while (fgets(buffer, RCIN_NAVIO_MAX_SIZE_LINE, fd) != NULL) {
|
|
||||||
flag = strstr(buffer, hardware_description_entry);
|
|
||||||
|
|
||||||
if (flag != NULL) {
|
|
||||||
if (strstr(buffer, v2) != NULL) {
|
|
||||||
printf("Raspberry Pi 2 with BCM2709!\n");
|
|
||||||
fclose(fd);
|
|
||||||
return 2;
|
|
||||||
}
|
|
||||||
else if (strstr(buffer, v1) != NULL) {
|
|
||||||
printf("Raspberry Pi 1 with BCM2708!\n");
|
|
||||||
fclose(fd);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
//Physical addresses of peripheral depends on Raspberry Pi's version
|
//Physical addresses of peripheral depends on Raspberry Pi's version
|
||||||
void LinuxRCInput_Navio::set_physical_addresses(int version)
|
void LinuxRCInput_Navio::set_physical_addresses(int version)
|
||||||
{
|
{
|
||||||
@ -420,7 +392,7 @@ LinuxRCInput_Navio::LinuxRCInput_Navio():
|
|||||||
last_signal(228),
|
last_signal(228),
|
||||||
state(RCIN_NAVIO_INITIAL_STATE)
|
state(RCIN_NAVIO_INITIAL_STATE)
|
||||||
{
|
{
|
||||||
int version = get_raspberry_pi_version();
|
int version = static_cast<LinuxUtilNavio*>(hal.util)->get_rpi_version();
|
||||||
set_physical_addresses(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"
|
//Init memory for buffer and for DMA control blocks. See comments in "init_ctrl_data()" to understand values "2" and "113"
|
||||||
|
69
libraries/AP_HAL_Linux/Util_Navio.cpp
Normal file
69
libraries/AP_HAL_Linux/Util_Navio.cpp
Normal file
@ -0,0 +1,69 @@
|
|||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdarg.h>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <time.h>
|
||||||
|
|
||||||
|
#include "Util_Navio.h"
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
using namespace Linux;
|
||||||
|
|
||||||
|
LinuxUtilNavio::LinuxUtilNavio()
|
||||||
|
{
|
||||||
|
_check_rpi_version();
|
||||||
|
}
|
||||||
|
|
||||||
|
#define MAX_SIZE_LINE 50
|
||||||
|
int LinuxUtilNavio::_check_rpi_version()
|
||||||
|
{
|
||||||
|
char buffer[MAX_SIZE_LINE];
|
||||||
|
const char* hardware_description_entry = "Hardware";
|
||||||
|
const char* v1 = "BCM2708";
|
||||||
|
const char* v2 = "BCM2709";
|
||||||
|
char* flag;
|
||||||
|
FILE* fd;
|
||||||
|
|
||||||
|
fd = fopen("/proc/cpuinfo", "r");
|
||||||
|
|
||||||
|
while (fgets(buffer, MAX_SIZE_LINE, fd) != NULL) {
|
||||||
|
flag = strstr(buffer, hardware_description_entry);
|
||||||
|
if (flag != NULL) {
|
||||||
|
if (strstr(buffer, v2) != NULL) {
|
||||||
|
printf("Raspberry Pi 2 with BCM2709!\n");
|
||||||
|
fclose(fd);
|
||||||
|
|
||||||
|
_rpi_version = 2;
|
||||||
|
return _rpi_version;
|
||||||
|
}
|
||||||
|
else if (strstr(buffer, v1) != NULL) {
|
||||||
|
printf("Raspberry Pi 1 with BCM2708!\n");
|
||||||
|
fclose(fd);
|
||||||
|
|
||||||
|
_rpi_version = 1;
|
||||||
|
return _rpi_version;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* defaults to 1 */
|
||||||
|
fprintf(stderr, "Could not detect RPi version, defaulting to 1\n");
|
||||||
|
fclose(fd);
|
||||||
|
|
||||||
|
_rpi_version = 1;
|
||||||
|
return _rpi_version;
|
||||||
|
}
|
||||||
|
|
||||||
|
int LinuxUtilNavio::get_rpi_version() const
|
||||||
|
{
|
||||||
|
return _rpi_version;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
17
libraries/AP_HAL_Linux/Util_Navio.h
Normal file
17
libraries/AP_HAL_Linux/Util_Navio.h
Normal file
@ -0,0 +1,17 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "Util.h"
|
||||||
|
|
||||||
|
class Linux::LinuxUtilNavio : public Linux::LinuxUtil {
|
||||||
|
public:
|
||||||
|
LinuxUtilNavio();
|
||||||
|
/* return the Raspberry Pi version */
|
||||||
|
int get_rpi_version() const;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
// Called in the constructor once
|
||||||
|
int _check_rpi_version();
|
||||||
|
|
||||||
|
private:
|
||||||
|
int _rpi_version = 0;
|
||||||
|
};
|
Loading…
Reference in New Issue
Block a user