AP_HAL_Linux: remove prefix from AP_HAL_Linux classes
We have already a Linux namespace, so there's no need to prefix Linux on all names.
This commit is contained in:
parent
19b31ccff1
commit
2ac96b942c
@ -2,46 +2,41 @@
|
||||
#ifndef __AP_HAL_LINUX_NAMESPACE_H__
|
||||
#define __AP_HAL_LINUX_NAMESPACE_H__
|
||||
|
||||
/* While not strictly required, names inside the Linux namespace are prefixed
|
||||
* with Linux for clarity. (Some of our users aren't familiar with all of the
|
||||
* C++ namespace rules.)
|
||||
*/
|
||||
|
||||
namespace Linux {
|
||||
class LinuxUARTDriver;
|
||||
class LinuxSPIUARTDriver;
|
||||
class LinuxRPIOUARTDriver;
|
||||
class LinuxI2CDriver;
|
||||
class LinuxSPIDeviceManager;
|
||||
class LinuxSPIDeviceDriver;
|
||||
class LinuxAnalogSource;
|
||||
class LinuxAnalogIn;
|
||||
class LinuxStorage;
|
||||
class LinuxGPIO_BBB;
|
||||
class LinuxGPIO_RPI;
|
||||
class LinuxStorage;
|
||||
class LinuxStorage_FRAM;
|
||||
class LinuxDigitalSource;
|
||||
class LinuxRCInput;
|
||||
class LinuxRCInput_PRU;
|
||||
class LinuxRCInput_AioPRU;
|
||||
class LinuxRCInput_Navio;
|
||||
class LinuxRCInput_Raspilot;
|
||||
class LinuxRCInput_ZYNQ;
|
||||
class LinuxRCInput_UDP;
|
||||
class LinuxRCOutput_PRU;
|
||||
class LinuxRCOutput_AioPRU;
|
||||
class LinuxRCOutput_PCA9685;
|
||||
class LinuxRCOutput_Raspilot;
|
||||
class LinuxRCOutput_ZYNQ;
|
||||
class LinuxRCOutput_Bebop;
|
||||
class LinuxSemaphore;
|
||||
class LinuxScheduler;
|
||||
class LinuxUtil;
|
||||
class LinuxUtilRPI;
|
||||
class ToneAlarm; //limit the scope of ToneAlarm driver to Linux_HAL only
|
||||
class LinuxHeat;
|
||||
class LinuxHeatPwm;
|
||||
class UARTDriver;
|
||||
class SPIUARTDriver;
|
||||
class RPIOUARTDriver;
|
||||
class I2CDriver;
|
||||
class SPIDeviceManager;
|
||||
class SPIDeviceDriver;
|
||||
class AnalogSource;
|
||||
class AnalogIn;
|
||||
class Storage;
|
||||
class GPIO_BBB;
|
||||
class GPIO_RPI;
|
||||
class Storage;
|
||||
class Storage_FRAM;
|
||||
class DigitalSource;
|
||||
class RCInput;
|
||||
class RCInput_PRU;
|
||||
class RCInput_AioPRU;
|
||||
class RCInput_Navio;
|
||||
class RCInput_Raspilot;
|
||||
class RCInput_ZYNQ;
|
||||
class RCInput_UDP;
|
||||
class RCOutput_PRU;
|
||||
class RCOutput_AioPRU;
|
||||
class RCOutput_PCA9685;
|
||||
class RCOutput_Raspilot;
|
||||
class RCOutput_ZYNQ;
|
||||
class RCOutput_Bebop;
|
||||
class Semaphore;
|
||||
class Scheduler;
|
||||
class Util;
|
||||
class UtilRPI;
|
||||
class ToneAlarm;
|
||||
class Heat;
|
||||
class HeatPwm;
|
||||
}
|
||||
|
||||
#endif // __AP_HAL_LINUX_NAMESPACE_H__
|
||||
|
@ -5,43 +5,43 @@
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
LinuxAnalogSource::LinuxAnalogSource(float v) :
|
||||
AnalogSource::AnalogSource(float v) :
|
||||
_v(v)
|
||||
{}
|
||||
|
||||
float LinuxAnalogSource::read_average() {
|
||||
float AnalogSource::read_average() {
|
||||
return _v;
|
||||
}
|
||||
|
||||
float LinuxAnalogSource::voltage_average() {
|
||||
float AnalogSource::voltage_average() {
|
||||
return 5.0 * _v / 1024.0;
|
||||
}
|
||||
|
||||
float LinuxAnalogSource::voltage_latest() {
|
||||
float AnalogSource::voltage_latest() {
|
||||
return 5.0 * _v / 1024.0;
|
||||
}
|
||||
|
||||
float LinuxAnalogSource::read_latest() {
|
||||
float AnalogSource::read_latest() {
|
||||
return _v;
|
||||
}
|
||||
|
||||
void LinuxAnalogSource::set_pin(uint8_t p)
|
||||
void AnalogSource::set_pin(uint8_t p)
|
||||
{}
|
||||
|
||||
void LinuxAnalogSource::set_stop_pin(uint8_t p)
|
||||
void AnalogSource::set_stop_pin(uint8_t p)
|
||||
{}
|
||||
|
||||
void LinuxAnalogSource::set_settle_time(uint16_t settle_time_ms)
|
||||
void AnalogSource::set_settle_time(uint16_t settle_time_ms)
|
||||
{}
|
||||
|
||||
LinuxAnalogIn::LinuxAnalogIn()
|
||||
AnalogIn::AnalogIn()
|
||||
{}
|
||||
|
||||
void LinuxAnalogIn::init(void* machtnichts)
|
||||
void AnalogIn::init(void* machtnichts)
|
||||
{}
|
||||
|
||||
AP_HAL::AnalogSource* LinuxAnalogIn::channel(int16_t n) {
|
||||
return new LinuxAnalogSource(1.11);
|
||||
AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) {
|
||||
return new AnalogSource(1.11);
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
class Linux::LinuxAnalogSource : public AP_HAL::AnalogSource {
|
||||
class Linux::AnalogSource : public AP_HAL::AnalogSource {
|
||||
public:
|
||||
LinuxAnalogSource(float v);
|
||||
AnalogSource(float v);
|
||||
float read_average();
|
||||
float read_latest();
|
||||
void set_pin(uint8_t p);
|
||||
@ -19,9 +19,9 @@ private:
|
||||
float _v;
|
||||
};
|
||||
|
||||
class Linux::LinuxAnalogIn : public AP_HAL::AnalogIn {
|
||||
class Linux::AnalogIn : public AP_HAL::AnalogIn {
|
||||
public:
|
||||
LinuxAnalogIn();
|
||||
AnalogIn();
|
||||
void init(void* implspecific);
|
||||
AP_HAL::AnalogSource* channel(int16_t n);
|
||||
|
||||
|
@ -7,28 +7,28 @@ using namespace Linux;
|
||||
|
||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
LinuxDigitalSource::LinuxDigitalSource(uint8_t v) :
|
||||
DigitalSource::DigitalSource(uint8_t v) :
|
||||
_v(v)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void LinuxDigitalSource::mode(uint8_t output)
|
||||
void DigitalSource::mode(uint8_t output)
|
||||
{
|
||||
hal.gpio->pinMode(_v, output);
|
||||
}
|
||||
|
||||
uint8_t LinuxDigitalSource::read()
|
||||
uint8_t DigitalSource::read()
|
||||
{
|
||||
return hal.gpio->read(_v);
|
||||
}
|
||||
|
||||
void LinuxDigitalSource::write(uint8_t value)
|
||||
void DigitalSource::write(uint8_t value)
|
||||
{
|
||||
return hal.gpio->write(_v,value);
|
||||
}
|
||||
|
||||
void LinuxDigitalSource::toggle()
|
||||
void DigitalSource::toggle()
|
||||
{
|
||||
write(!read());
|
||||
}
|
||||
|
@ -10,9 +10,9 @@
|
||||
#include "GPIO_RPI.h"
|
||||
#endif
|
||||
|
||||
class Linux::LinuxDigitalSource : public AP_HAL::DigitalSource {
|
||||
class Linux::DigitalSource : public AP_HAL::DigitalSource {
|
||||
public:
|
||||
LinuxDigitalSource(uint8_t v);
|
||||
DigitalSource(uint8_t v);
|
||||
void mode(uint8_t output);
|
||||
uint8_t read();
|
||||
void write(uint8_t value);
|
||||
|
@ -18,10 +18,10 @@
|
||||
using namespace Linux;
|
||||
|
||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
LinuxGPIO_BBB::LinuxGPIO_BBB()
|
||||
GPIO_BBB::GPIO_BBB()
|
||||
{}
|
||||
|
||||
void LinuxGPIO_BBB::init()
|
||||
void GPIO_BBB::init()
|
||||
{
|
||||
#if LINUX_GPIO_NUM_BANKS == 4
|
||||
int mem_fd;
|
||||
@ -62,7 +62,7 @@ void LinuxGPIO_BBB::init()
|
||||
#endif // LINUX_GPIO_NUM_BANKS
|
||||
}
|
||||
|
||||
void LinuxGPIO_BBB::pinMode(uint8_t pin, uint8_t output)
|
||||
void GPIO_BBB::pinMode(uint8_t pin, uint8_t output)
|
||||
{
|
||||
uint8_t bank = pin/32;
|
||||
uint8_t bankpin = pin & 0x1F;
|
||||
@ -76,13 +76,13 @@ void LinuxGPIO_BBB::pinMode(uint8_t pin, uint8_t output)
|
||||
}
|
||||
}
|
||||
|
||||
int8_t LinuxGPIO_BBB::analogPinToDigitalPin(uint8_t pin)
|
||||
int8_t GPIO_BBB::analogPinToDigitalPin(uint8_t pin)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
uint8_t LinuxGPIO_BBB::read(uint8_t pin) {
|
||||
uint8_t GPIO_BBB::read(uint8_t pin) {
|
||||
|
||||
uint8_t bank = pin/32;
|
||||
uint8_t bankpin = pin & 0x1F;
|
||||
@ -93,7 +93,7 @@ uint8_t LinuxGPIO_BBB::read(uint8_t pin) {
|
||||
|
||||
}
|
||||
|
||||
void LinuxGPIO_BBB::write(uint8_t pin, uint8_t value)
|
||||
void GPIO_BBB::write(uint8_t pin, uint8_t value)
|
||||
{
|
||||
uint8_t bank = pin/32;
|
||||
uint8_t bankpin = pin & 0x1F;
|
||||
@ -107,23 +107,23 @@ void LinuxGPIO_BBB::write(uint8_t pin, uint8_t value)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxGPIO_BBB::toggle(uint8_t pin)
|
||||
void GPIO_BBB::toggle(uint8_t pin)
|
||||
{
|
||||
write(pin, !read(pin));
|
||||
}
|
||||
|
||||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* LinuxGPIO_BBB::channel(uint16_t n) {
|
||||
return new LinuxDigitalSource(n);
|
||||
AP_HAL::DigitalSource* GPIO_BBB::channel(uint16_t n) {
|
||||
return new DigitalSource(n);
|
||||
}
|
||||
|
||||
/* Interrupt interface: */
|
||||
bool LinuxGPIO_BBB::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
|
||||
bool GPIO_BBB::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
bool LinuxGPIO_BBB::usb_connected(void)
|
||||
bool GPIO_BBB::usb_connected(void)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
@ -105,7 +105,7 @@
|
||||
#define BBB_P9_41 20
|
||||
#define BBB_P9_42 7
|
||||
|
||||
class Linux::LinuxGPIO_BBB : public AP_HAL::GPIO {
|
||||
class Linux::GPIO_BBB : public AP_HAL::GPIO {
|
||||
private:
|
||||
struct GPIO {
|
||||
volatile uint32_t *base;
|
||||
@ -115,7 +115,7 @@ private:
|
||||
} gpio_bank[LINUX_GPIO_NUM_BANKS];
|
||||
|
||||
public:
|
||||
LinuxGPIO_BBB();
|
||||
GPIO_BBB();
|
||||
void init();
|
||||
void pinMode(uint8_t pin, uint8_t output);
|
||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
||||
|
@ -19,12 +19,12 @@
|
||||
using namespace Linux;
|
||||
|
||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
LinuxGPIO_RPI::LinuxGPIO_RPI()
|
||||
GPIO_RPI::GPIO_RPI()
|
||||
{}
|
||||
|
||||
void LinuxGPIO_RPI::init()
|
||||
void GPIO_RPI::init()
|
||||
{
|
||||
int rpi_version = LinuxUtilRPI::from(hal.util)->get_rpi_version();
|
||||
int rpi_version = UtilRPI::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);
|
||||
@ -72,7 +72,7 @@ void LinuxGPIO_RPI::init()
|
||||
clk = (volatile uint32_t *)clk_map;
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::pinMode(uint8_t pin, uint8_t output)
|
||||
void GPIO_RPI::pinMode(uint8_t pin, uint8_t output)
|
||||
{
|
||||
if (output == HAL_GPIO_INPUT) {
|
||||
GPIO_MODE_IN(pin);
|
||||
@ -82,7 +82,7 @@ void LinuxGPIO_RPI::pinMode(uint8_t pin, uint8_t output)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
|
||||
void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
|
||||
{
|
||||
if (output == HAL_GPIO_INPUT) {
|
||||
GPIO_MODE_IN(pin);
|
||||
@ -95,18 +95,18 @@ void LinuxGPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
|
||||
}
|
||||
}
|
||||
|
||||
int8_t LinuxGPIO_RPI::analogPinToDigitalPin(uint8_t pin)
|
||||
int8_t GPIO_RPI::analogPinToDigitalPin(uint8_t pin)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint8_t LinuxGPIO_RPI::read(uint8_t pin)
|
||||
uint8_t GPIO_RPI::read(uint8_t pin)
|
||||
{
|
||||
uint32_t value = GPIO_GET(pin);
|
||||
return value ? 1: 0;
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::write(uint8_t pin, uint8_t value)
|
||||
void GPIO_RPI::write(uint8_t pin, uint8_t value)
|
||||
{
|
||||
if (value == LOW) {
|
||||
GPIO_SET_LOW = 1 << pin;
|
||||
@ -115,22 +115,22 @@ void LinuxGPIO_RPI::write(uint8_t pin, uint8_t value)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::toggle(uint8_t pin)
|
||||
void GPIO_RPI::toggle(uint8_t pin)
|
||||
{
|
||||
write(pin, !read(pin));
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::setPWMPeriod(uint8_t pin, uint32_t time_us)
|
||||
void GPIO_RPI::setPWMPeriod(uint8_t pin, uint32_t time_us)
|
||||
{
|
||||
setPWM0Period(time_us);
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::setPWMDuty(uint8_t pin, uint8_t percent)
|
||||
void GPIO_RPI::setPWMDuty(uint8_t pin, uint8_t percent)
|
||||
{
|
||||
setPWM0Duty(percent);
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::setPWM0Period(uint32_t time_us)
|
||||
void GPIO_RPI::setPWM0Period(uint32_t time_us)
|
||||
{
|
||||
// stop clock and waiting for busy flag doesn't work, so kill clock
|
||||
*(clk + PWMCLK_CNTL) = 0x5A000000 | (1 << 5);
|
||||
@ -165,7 +165,7 @@ void LinuxGPIO_RPI::setPWM0Period(uint32_t time_us)
|
||||
*(pwm + PWM_CTL) = 3;
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::setPWM0Duty(uint8_t percent)
|
||||
void GPIO_RPI::setPWM0Duty(uint8_t percent)
|
||||
{
|
||||
int bitCount;
|
||||
unsigned int bits = 0;
|
||||
@ -183,17 +183,17 @@ void LinuxGPIO_RPI::setPWM0Duty(uint8_t percent)
|
||||
}
|
||||
|
||||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* LinuxGPIO_RPI::channel(uint16_t n) {
|
||||
return new LinuxDigitalSource(n);
|
||||
AP_HAL::DigitalSource* GPIO_RPI::channel(uint16_t n) {
|
||||
return new DigitalSource(n);
|
||||
}
|
||||
|
||||
/* Interrupt interface: */
|
||||
bool LinuxGPIO_RPI::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
|
||||
bool GPIO_RPI::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
bool LinuxGPIO_RPI::usb_connected(void)
|
||||
bool GPIO_RPI::usb_connected(void)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
@ -64,7 +64,7 @@
|
||||
#define RPI_GPIO_30 30 // Pin 5
|
||||
#define RPI_GPIO_31 31 // Pin 6
|
||||
|
||||
class Linux::LinuxGPIO_RPI : public AP_HAL::GPIO {
|
||||
class Linux::GPIO_RPI : public AP_HAL::GPIO {
|
||||
private:
|
||||
int mem_fd;
|
||||
void *gpio_map;
|
||||
@ -77,7 +77,7 @@ private:
|
||||
void setPWM0Duty(uint8_t percent);
|
||||
|
||||
public:
|
||||
LinuxGPIO_RPI();
|
||||
GPIO_RPI();
|
||||
void init();
|
||||
void pinMode(uint8_t pin, uint8_t output);
|
||||
void pinMode(uint8_t pin, uint8_t output, uint8_t alt);
|
||||
|
@ -17,61 +17,61 @@
|
||||
using namespace Linux;
|
||||
|
||||
// 3 serial ports on Linux for now
|
||||
static LinuxUARTDriver uartADriver(true);
|
||||
static UARTDriver uartADriver(true);
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||
static LinuxSPIUARTDriver uartBDriver;
|
||||
static SPIUARTDriver uartBDriver;
|
||||
#else
|
||||
static LinuxUARTDriver uartBDriver(false);
|
||||
static UARTDriver uartBDriver(false);
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
static LinuxRPIOUARTDriver uartCDriver;
|
||||
static RPIOUARTDriver uartCDriver;
|
||||
#else
|
||||
static LinuxUARTDriver uartCDriver(false);
|
||||
static UARTDriver uartCDriver(false);
|
||||
#endif
|
||||
static LinuxUARTDriver uartEDriver(false);
|
||||
static UARTDriver uartEDriver(false);
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
static LinuxSemaphore i2cSemaphore0;
|
||||
static LinuxI2CDriver i2cDriver0(&i2cSemaphore0, "/dev/i2c-0");
|
||||
static LinuxSemaphore i2cSemaphore1;
|
||||
static LinuxI2CDriver i2cDriver1(&i2cSemaphore1, "/dev/i2c-1");
|
||||
static LinuxSemaphore i2cSemaphore2;
|
||||
static LinuxI2CDriver i2cDriver2(&i2cSemaphore2, "/dev/i2c-2");
|
||||
static Semaphore i2cSemaphore0;
|
||||
static I2CDriver i2cDriver0(&i2cSemaphore0, "/dev/i2c-0");
|
||||
static Semaphore i2cSemaphore1;
|
||||
static I2CDriver i2cDriver1(&i2cSemaphore1, "/dev/i2c-1");
|
||||
static Semaphore i2cSemaphore2;
|
||||
static I2CDriver i2cDriver2(&i2cSemaphore2, "/dev/i2c-2");
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
||||
static LinuxSemaphore i2cSemaphore0;
|
||||
static LinuxI2CDriver i2cDriver0(&i2cSemaphore0, "/dev/i2c-2");
|
||||
static Semaphore i2cSemaphore0;
|
||||
static I2CDriver i2cDriver0(&i2cSemaphore0, "/dev/i2c-2");
|
||||
#else
|
||||
static LinuxSemaphore i2cSemaphore0;
|
||||
static LinuxI2CDriver i2cDriver0(&i2cSemaphore0, "/dev/i2c-1");
|
||||
static Semaphore i2cSemaphore0;
|
||||
static I2CDriver i2cDriver0(&i2cSemaphore0, "/dev/i2c-1");
|
||||
#endif
|
||||
static LinuxSPIDeviceManager spiDeviceManager;
|
||||
static SPIDeviceManager spiDeviceManager;
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||
static NavioAnalogIn analogIn;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
static RaspilotAnalogIn analogIn;
|
||||
#else
|
||||
static LinuxAnalogIn analogIn;
|
||||
static AnalogIn analogIn;
|
||||
#endif
|
||||
|
||||
/*
|
||||
select between FRAM and FS
|
||||
*/
|
||||
#if LINUX_STORAGE_USE_FRAM == 1
|
||||
static LinuxStorage_FRAM storageDriver;
|
||||
static Storage_FRAM storageDriver;
|
||||
#else
|
||||
static LinuxStorage storageDriver;
|
||||
static Storage storageDriver;
|
||||
#endif
|
||||
|
||||
/*
|
||||
use the BBB gpio driver on ERLE, PXF and BBBMINI
|
||||
*/
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
||||
static LinuxGPIO_BBB gpioDriver;
|
||||
static GPIO_BBB gpioDriver;
|
||||
/*
|
||||
use the RPI gpio driver on Navio
|
||||
*/
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
static LinuxGPIO_RPI gpioDriver;
|
||||
static GPIO_RPI gpioDriver;
|
||||
#else
|
||||
static Empty::EmptyGPIO gpioDriver;
|
||||
#endif
|
||||
@ -80,51 +80,51 @@ static Empty::EmptyGPIO gpioDriver;
|
||||
use the PRU based RCInput driver on ERLE and PXF
|
||||
*/
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
|
||||
static LinuxRCInput_PRU rcinDriver;
|
||||
static RCInput_PRU rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
||||
static LinuxRCInput_AioPRU rcinDriver;
|
||||
static RCInput_AioPRU rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||
static LinuxRCInput_Navio rcinDriver;
|
||||
static RCInput_Navio rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
static LinuxRCInput_Raspilot rcinDriver;
|
||||
static RCInput_Raspilot rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ZYNQ
|
||||
static LinuxRCInput_ZYNQ rcinDriver;
|
||||
static RCInput_ZYNQ rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
static LinuxRCInput_UDP rcinDriver;
|
||||
static RCInput_UDP rcinDriver;
|
||||
#else
|
||||
static LinuxRCInput rcinDriver;
|
||||
static RCInput rcinDriver;
|
||||
#endif
|
||||
|
||||
/*
|
||||
use the PRU based RCOutput driver on ERLE and PXF
|
||||
*/
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
|
||||
static LinuxRCOutput_PRU rcoutDriver;
|
||||
static RCOutput_PRU rcoutDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
||||
static LinuxRCOutput_AioPRU rcoutDriver;
|
||||
static RCOutput_AioPRU rcoutDriver;
|
||||
/*
|
||||
use the PCA9685 based RCOutput driver on Navio
|
||||
*/
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||
static LinuxRCOutput_PCA9685 rcoutDriver(PCA9685_PRIMARY_ADDRESS, true, 3, RPI_GPIO_27);
|
||||
static RCOutput_PCA9685 rcoutDriver(PCA9685_PRIMARY_ADDRESS, true, 3, RPI_GPIO_27);
|
||||
/*
|
||||
use the STM32 based RCOutput driver on Raspilot
|
||||
*/
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
static LinuxRCOutput_Raspilot rcoutDriver;
|
||||
static RCOutput_Raspilot rcoutDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ZYNQ
|
||||
static LinuxRCOutput_ZYNQ rcoutDriver;
|
||||
static RCOutput_ZYNQ rcoutDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
static LinuxRCOutput_Bebop rcoutDriver;
|
||||
static RCOutput_Bebop rcoutDriver;
|
||||
#else
|
||||
static Empty::EmptyRCOutput rcoutDriver;
|
||||
#endif
|
||||
|
||||
static LinuxScheduler schedulerInstance;
|
||||
static Scheduler schedulerInstance;
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
static LinuxUtilRPI utilInstance;
|
||||
static UtilRPI utilInstance;
|
||||
#else
|
||||
static LinuxUtil utilInstance;
|
||||
static Util utilInstance;
|
||||
#endif
|
||||
|
||||
HAL_Linux::HAL_Linux() :
|
||||
|
@ -17,7 +17,7 @@
|
||||
#ifndef __HEAT_H__
|
||||
#define __HEAT_H__
|
||||
|
||||
class Linux::LinuxHeat {
|
||||
class Linux::Heat {
|
||||
public:
|
||||
virtual void set_imu_temp(float current) { }
|
||||
};
|
||||
|
@ -41,7 +41,7 @@ using namespace Linux;
|
||||
* argument : pwm_sysfs_path is the path to the pwm directory,
|
||||
* i.e /sys/class/pwm/pwm_6 on the bebop
|
||||
*/
|
||||
LinuxHeatPwm::LinuxHeatPwm(const char* pwm_sysfs_path, float Kp, float Ki, uint32_t period_ns, float target) :
|
||||
HeatPwm::HeatPwm(const char* pwm_sysfs_path, float Kp, float Ki, uint32_t period_ns, float target) :
|
||||
_Kp(Kp),
|
||||
_Ki(Ki),
|
||||
_period_ns(period_ns),
|
||||
@ -86,7 +86,7 @@ LinuxHeatPwm::LinuxHeatPwm(const char* pwm_sysfs_path, float Kp, float Ki, uint3
|
||||
_set_run();
|
||||
}
|
||||
|
||||
void LinuxHeatPwm::set_imu_temp(float current)
|
||||
void HeatPwm::set_imu_temp(float current)
|
||||
{
|
||||
float error, output;
|
||||
|
||||
@ -115,21 +115,21 @@ void LinuxHeatPwm::set_imu_temp(float current)
|
||||
_last_temp_update = hal.scheduler->millis();
|
||||
}
|
||||
|
||||
void LinuxHeatPwm::_set_duty(uint32_t duty)
|
||||
void HeatPwm::_set_duty(uint32_t duty)
|
||||
{
|
||||
if (dprintf(_duty_fd, "0x%x", duty) < 0) {
|
||||
perror("pwm set_duty");
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxHeatPwm::_set_period(uint32_t period)
|
||||
void HeatPwm::_set_period(uint32_t period)
|
||||
{
|
||||
if (dprintf(_period_fd, "0x%x", period) < 0) {
|
||||
perror("pwm set_period");
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxHeatPwm::_set_run()
|
||||
void HeatPwm::_set_run()
|
||||
{
|
||||
if (dprintf(_run_fd, "1") < 0) {
|
||||
perror("pwm set_run");
|
||||
|
@ -20,9 +20,9 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "Heat.h"
|
||||
|
||||
class Linux::LinuxHeatPwm : public Linux::LinuxHeat {
|
||||
class Linux::HeatPwm : public Linux::Heat {
|
||||
public:
|
||||
LinuxHeatPwm(const char* pwm_sysfs_path, float Kp, float Ki,uint32_t period_ns, float target);
|
||||
HeatPwm(const char* pwm_sysfs_path, float Kp, float Ki,uint32_t period_ns, float target);
|
||||
void set_imu_temp(float current)override;
|
||||
|
||||
private:
|
||||
|
@ -26,13 +26,13 @@ using namespace Linux;
|
||||
/*
|
||||
constructor
|
||||
*/
|
||||
LinuxI2CDriver::LinuxI2CDriver(AP_HAL::Semaphore* semaphore, const char *device) :
|
||||
I2CDriver::I2CDriver(AP_HAL::Semaphore* semaphore, const char *device) :
|
||||
_semaphore(semaphore)
|
||||
{
|
||||
_device = strdup(device);
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
|
||||
if (!((LinuxUtil*)hal.util)->is_chardev_node(_device))
|
||||
if (!((Util*)hal.util)->is_chardev_node(_device))
|
||||
hal.scheduler->panic("I2C device is not a chardev node");
|
||||
#endif
|
||||
}
|
||||
@ -41,7 +41,7 @@ LinuxI2CDriver::LinuxI2CDriver(AP_HAL::Semaphore* semaphore, const char *device)
|
||||
* udevadm info -q path /dev/<i2c-device>'. This constructor can be used when
|
||||
* the number of the I2C bus is not stable across reboots. It matches the
|
||||
* first device with a prefix in @devpaths */
|
||||
LinuxI2CDriver::LinuxI2CDriver(AP_HAL::Semaphore* semaphore,
|
||||
I2CDriver::I2CDriver(AP_HAL::Semaphore* semaphore,
|
||||
const char * const devpaths[]) :
|
||||
_semaphore(semaphore)
|
||||
{
|
||||
@ -84,11 +84,11 @@ LinuxI2CDriver::LinuxI2CDriver(AP_HAL::Semaphore* semaphore,
|
||||
|
||||
closedir(d);
|
||||
|
||||
if (!((LinuxUtil*)hal.util)->is_chardev_node(_device))
|
||||
if (!((Util*)hal.util)->is_chardev_node(_device))
|
||||
hal.scheduler->panic("I2C device is not a chardev node");
|
||||
}
|
||||
|
||||
LinuxI2CDriver::~LinuxI2CDriver()
|
||||
I2CDriver::~I2CDriver()
|
||||
{
|
||||
free(_device);
|
||||
}
|
||||
@ -96,7 +96,7 @@ LinuxI2CDriver::~LinuxI2CDriver()
|
||||
/*
|
||||
called from HAL class init()
|
||||
*/
|
||||
void LinuxI2CDriver::begin()
|
||||
void I2CDriver::begin()
|
||||
{
|
||||
if (_fd != -1) {
|
||||
close(_fd);
|
||||
@ -104,7 +104,7 @@ void LinuxI2CDriver::begin()
|
||||
_fd = open(_device, O_RDWR);
|
||||
}
|
||||
|
||||
void LinuxI2CDriver::end()
|
||||
void I2CDriver::end()
|
||||
{
|
||||
if (_fd != -1) {
|
||||
::close(_fd);
|
||||
@ -115,7 +115,7 @@ void LinuxI2CDriver::end()
|
||||
/*
|
||||
tell the I2C library what device we want to talk to
|
||||
*/
|
||||
bool LinuxI2CDriver::set_address(uint8_t addr)
|
||||
bool I2CDriver::set_address(uint8_t addr)
|
||||
{
|
||||
if (_fd == -1) {
|
||||
return false;
|
||||
@ -127,17 +127,17 @@ bool LinuxI2CDriver::set_address(uint8_t addr)
|
||||
return true;
|
||||
}
|
||||
|
||||
void LinuxI2CDriver::setTimeout(uint16_t ms)
|
||||
void I2CDriver::setTimeout(uint16_t ms)
|
||||
{
|
||||
// unimplemented
|
||||
}
|
||||
|
||||
void LinuxI2CDriver::setHighSpeed(bool active)
|
||||
void I2CDriver::setHighSpeed(bool active)
|
||||
{
|
||||
// unimplemented
|
||||
}
|
||||
|
||||
uint8_t LinuxI2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
uint8_t I2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
{
|
||||
if (!set_address(addr)) {
|
||||
return 1;
|
||||
@ -149,7 +149,7 @@ uint8_t LinuxI2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
}
|
||||
|
||||
|
||||
uint8_t LinuxI2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t I2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t len, uint8_t* data)
|
||||
{
|
||||
uint8_t buf[len+1];
|
||||
@ -175,7 +175,7 @@ static inline __s32 _i2c_smbus_access(int file, char read_write, __u8 command,
|
||||
return ioctl(file,I2C_SMBUS,&args);
|
||||
}
|
||||
|
||||
uint8_t LinuxI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
|
||||
uint8_t I2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
|
||||
{
|
||||
if (!set_address(addr)) {
|
||||
return 1;
|
||||
@ -189,7 +189,7 @@ uint8_t LinuxI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t LinuxI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
uint8_t I2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
{
|
||||
if (!set_address(addr)) {
|
||||
return 1;
|
||||
@ -200,7 +200,7 @@ uint8_t LinuxI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t LinuxI2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t I2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t len, uint8_t* data)
|
||||
{
|
||||
if (_fd == -1) {
|
||||
@ -236,7 +236,7 @@ uint8_t LinuxI2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
||||
}
|
||||
|
||||
|
||||
uint8_t LinuxI2CDriver::readRegistersMultiple(uint8_t addr, uint8_t reg,
|
||||
uint8_t I2CDriver::readRegistersMultiple(uint8_t addr, uint8_t reg,
|
||||
uint8_t len,
|
||||
uint8_t count, uint8_t* data)
|
||||
{
|
||||
@ -276,7 +276,7 @@ uint8_t LinuxI2CDriver::readRegistersMultiple(uint8_t addr, uint8_t reg,
|
||||
}
|
||||
|
||||
|
||||
uint8_t LinuxI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data)
|
||||
uint8_t I2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data)
|
||||
{
|
||||
if (!set_address(addr)) {
|
||||
return 1;
|
||||
@ -291,7 +291,7 @@ uint8_t LinuxI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data)
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t LinuxI2CDriver::lockup_count()
|
||||
uint8_t I2CDriver::lockup_count()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
@ -4,11 +4,11 @@
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
class Linux::LinuxI2CDriver : public AP_HAL::I2CDriver {
|
||||
class Linux::I2CDriver : public AP_HAL::I2CDriver {
|
||||
public:
|
||||
LinuxI2CDriver(AP_HAL::Semaphore* semaphore, const char *device);
|
||||
LinuxI2CDriver(AP_HAL::Semaphore* semaphore, const char * const devpaths[]);
|
||||
~LinuxI2CDriver();
|
||||
I2CDriver(AP_HAL::Semaphore* semaphore, const char *device);
|
||||
I2CDriver(AP_HAL::Semaphore* semaphore, const char * const devpaths[]);
|
||||
~I2CDriver();
|
||||
|
||||
void begin();
|
||||
void end();
|
||||
|
@ -22,27 +22,27 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
LinuxRCInput::LinuxRCInput() :
|
||||
RCInput::RCInput() :
|
||||
new_rc_input(false)
|
||||
{
|
||||
ppm_state._channel_counter = -1;
|
||||
}
|
||||
|
||||
void LinuxRCInput::init(void* machtnichts)
|
||||
void RCInput::init(void* machtnichts)
|
||||
{
|
||||
}
|
||||
|
||||
bool LinuxRCInput::new_input()
|
||||
bool RCInput::new_input()
|
||||
{
|
||||
return new_rc_input;
|
||||
}
|
||||
|
||||
uint8_t LinuxRCInput::num_channels()
|
||||
uint8_t RCInput::num_channels()
|
||||
{
|
||||
return _num_channels;
|
||||
}
|
||||
|
||||
uint16_t LinuxRCInput::read(uint8_t ch)
|
||||
uint16_t RCInput::read(uint8_t ch)
|
||||
{
|
||||
new_rc_input = false;
|
||||
if (_override[ch]) {
|
||||
@ -54,7 +54,7 @@ uint16_t LinuxRCInput::read(uint8_t ch)
|
||||
return _pwm_values[ch];
|
||||
}
|
||||
|
||||
uint8_t LinuxRCInput::read(uint16_t* periods, uint8_t len)
|
||||
uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
||||
{
|
||||
uint8_t i;
|
||||
for (i=0; i<len; i++) {
|
||||
@ -68,7 +68,7 @@ uint8_t LinuxRCInput::read(uint16_t* periods, uint8_t len)
|
||||
return (i+1);
|
||||
}
|
||||
|
||||
bool LinuxRCInput::set_overrides(int16_t *overrides, uint8_t len)
|
||||
bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
|
||||
{
|
||||
bool res = false;
|
||||
if(len > LINUX_RC_INPUT_NUM_CHANNELS){
|
||||
@ -80,7 +80,7 @@ bool LinuxRCInput::set_overrides(int16_t *overrides, uint8_t len)
|
||||
return res;
|
||||
}
|
||||
|
||||
bool LinuxRCInput::set_override(uint8_t channel, int16_t override)
|
||||
bool RCInput::set_override(uint8_t channel, int16_t override)
|
||||
{
|
||||
if (override < 0) return false; /* -1: no change. */
|
||||
if (channel < LINUX_RC_INPUT_NUM_CHANNELS) {
|
||||
@ -93,7 +93,7 @@ bool LinuxRCInput::set_override(uint8_t channel, int16_t override)
|
||||
return false;
|
||||
}
|
||||
|
||||
void LinuxRCInput::clear_overrides()
|
||||
void RCInput::clear_overrides()
|
||||
{
|
||||
for (uint8_t i = 0; i < LINUX_RC_INPUT_NUM_CHANNELS; i++) {
|
||||
_override[i] = 0;
|
||||
@ -104,7 +104,7 @@ void LinuxRCInput::clear_overrides()
|
||||
/*
|
||||
process a PPM-sum pulse of the given width
|
||||
*/
|
||||
void LinuxRCInput::_process_ppmsum_pulse(uint16_t width_usec)
|
||||
void RCInput::_process_ppmsum_pulse(uint16_t width_usec)
|
||||
{
|
||||
if (width_usec >= 2700) {
|
||||
// a long pulse indicates the end of a frame. Reset the
|
||||
@ -153,7 +153,7 @@ void LinuxRCInput::_process_ppmsum_pulse(uint16_t width_usec)
|
||||
/*
|
||||
process a SBUS input pulse of the given width
|
||||
*/
|
||||
void LinuxRCInput::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
void RCInput::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
{
|
||||
// convert to bit widths, allowing for up to 1usec error, assuming 100000 bps
|
||||
uint16_t bits_s0 = (width_s0+1) / 10;
|
||||
@ -234,7 +234,7 @@ reset:
|
||||
memset(&sbus_state, 0, sizeof(sbus_state));
|
||||
}
|
||||
|
||||
void LinuxRCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
void RCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
{
|
||||
// convert to bit widths, allowing for up to 1usec error, assuming 115200 bps
|
||||
uint16_t bits_s0 = ((width_s0+4)*(uint32_t)115200) / 1000000;
|
||||
@ -315,7 +315,7 @@ reset:
|
||||
/*
|
||||
process a RC input pulse of the given width
|
||||
*/
|
||||
void LinuxRCInput::_process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
void RCInput::_process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
{
|
||||
#if 0
|
||||
// useful for debugging
|
||||
@ -340,7 +340,7 @@ void LinuxRCInput::_process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
/*
|
||||
* Update channel values directly
|
||||
*/
|
||||
void LinuxRCInput::_update_periods(uint16_t *periods, uint8_t len)
|
||||
void RCInput::_update_periods(uint16_t *periods, uint8_t len)
|
||||
{
|
||||
if (len > LINUX_RC_INPUT_NUM_CHANNELS) {
|
||||
len = LINUX_RC_INPUT_NUM_CHANNELS;
|
||||
|
@ -6,12 +6,12 @@
|
||||
|
||||
#define LINUX_RC_INPUT_NUM_CHANNELS 16
|
||||
|
||||
class Linux::LinuxRCInput : public AP_HAL::RCInput {
|
||||
class Linux::RCInput : public AP_HAL::RCInput {
|
||||
public:
|
||||
LinuxRCInput();
|
||||
RCInput();
|
||||
|
||||
static LinuxRCInput *from(AP_HAL::RCInput *rcinput) {
|
||||
return static_cast<LinuxRCInput*>(rcinput);
|
||||
static RCInput *from(AP_HAL::RCInput *rcinput) {
|
||||
return static_cast<RCInput*>(rcinput);
|
||||
}
|
||||
|
||||
virtual void init(void* machtnichts);
|
||||
|
@ -34,7 +34,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
void LinuxRCInput_AioPRU::init(void*)
|
||||
void RCInput_AioPRU::init(void*)
|
||||
{
|
||||
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC);
|
||||
if (mem_fd == -1) {
|
||||
@ -48,7 +48,7 @@ void LinuxRCInput_AioPRU::init(void*)
|
||||
/*
|
||||
called at 1kHz to check for new pulse capture data from the PRU
|
||||
*/
|
||||
void LinuxRCInput_AioPRU::_timer_tick()
|
||||
void RCInput_AioPRU::_timer_tick()
|
||||
{
|
||||
while (ring_buffer->ring_head != ring_buffer->ring_tail) {
|
||||
if (ring_buffer->ring_tail >= NUM_RING_ENTRIES) {
|
||||
|
@ -24,7 +24,7 @@
|
||||
// we use 300 ring buffer entries to guarantee that a full 25 byte
|
||||
// frame of 12 bits per byte
|
||||
|
||||
class Linux::LinuxRCInput_AioPRU : public Linux::LinuxRCInput
|
||||
class Linux::RCInput_AioPRU : public Linux::RCInput
|
||||
{
|
||||
public:
|
||||
void init(void*);
|
||||
|
@ -79,9 +79,9 @@ extern const AP_HAL::HAL& hal;
|
||||
using namespace Linux;
|
||||
|
||||
|
||||
volatile uint32_t *LinuxRCInput_Navio::pcm_reg;
|
||||
volatile uint32_t *LinuxRCInput_Navio::clk_reg;
|
||||
volatile uint32_t *LinuxRCInput_Navio::dma_reg;
|
||||
volatile uint32_t *RCInput_Navio::pcm_reg;
|
||||
volatile uint32_t *RCInput_Navio::clk_reg;
|
||||
volatile uint32_t *RCInput_Navio::dma_reg;
|
||||
|
||||
Memory_table::Memory_table()
|
||||
{
|
||||
@ -192,7 +192,7 @@ uint32_t Memory_table::get_page_count() const
|
||||
}
|
||||
|
||||
//Physical addresses of peripheral depends on Raspberry Pi's version
|
||||
void LinuxRCInput_Navio::set_physical_addresses(int version)
|
||||
void RCInput_Navio::set_physical_addresses(int version)
|
||||
{
|
||||
if (version == 1) {
|
||||
dma_base = RCIN_NAVIO_RPI1_DMA_BASE;
|
||||
@ -207,7 +207,7 @@ void LinuxRCInput_Navio::set_physical_addresses(int version)
|
||||
}
|
||||
|
||||
//Map peripheral to virtual memory
|
||||
void* LinuxRCInput_Navio::map_peripheral(uint32_t base, uint32_t len)
|
||||
void* RCInput_Navio::map_peripheral(uint32_t base, uint32_t len)
|
||||
{
|
||||
int fd = open("/dev/mem", O_RDWR);
|
||||
void * vaddr;
|
||||
@ -226,7 +226,7 @@ void* LinuxRCInput_Navio::map_peripheral(uint32_t base, uint32_t len)
|
||||
}
|
||||
|
||||
//Method to init DMA control block
|
||||
void LinuxRCInput_Navio::init_dma_cb(dma_cb_t** cbp, uint32_t mode, uint32_t source, uint32_t dest, uint32_t length, uint32_t stride, uint32_t next_cb)
|
||||
void RCInput_Navio::init_dma_cb(dma_cb_t** cbp, uint32_t mode, uint32_t source, uint32_t dest, uint32_t length, uint32_t stride, uint32_t next_cb)
|
||||
{
|
||||
(*cbp)->info = mode;
|
||||
(*cbp)->src = source;
|
||||
@ -236,13 +236,13 @@ void LinuxRCInput_Navio::init_dma_cb(dma_cb_t** cbp, uint32_t mode, uint32_t sou
|
||||
(*cbp)->stride = stride;
|
||||
}
|
||||
|
||||
void LinuxRCInput_Navio::stop_dma()
|
||||
void RCInput_Navio::stop_dma()
|
||||
{
|
||||
dma_reg[RCIN_NAVIO_DMA_CS | RCIN_NAVIO_DMA_CHANNEL << 8] = 0;
|
||||
}
|
||||
|
||||
/* We need to be sure that the DMA is stopped upon termination */
|
||||
void LinuxRCInput_Navio::termination_handler(int signum)
|
||||
void RCInput_Navio::termination_handler(int signum)
|
||||
{
|
||||
stop_dma();
|
||||
hal.scheduler->panic("Interrupted");
|
||||
@ -250,7 +250,7 @@ void LinuxRCInput_Navio::termination_handler(int signum)
|
||||
|
||||
|
||||
//This function is used to init DMA control blocks (setting sampling GPIO register, destination adresses, synchronization)
|
||||
void LinuxRCInput_Navio::init_ctrl_data()
|
||||
void RCInput_Navio::init_ctrl_data()
|
||||
{
|
||||
uint32_t phys_fifo_addr;
|
||||
uint32_t dest = 0;
|
||||
@ -329,7 +329,7 @@ void LinuxRCInput_Navio::init_ctrl_data()
|
||||
See BCM2835 documentation:
|
||||
http://www.raspberrypi.org/wp-content/uploads/2012/02/BCM2835-ARM-Peripherals.pdf
|
||||
*/
|
||||
void LinuxRCInput_Navio::init_PCM()
|
||||
void RCInput_Navio::init_PCM()
|
||||
{
|
||||
pcm_reg[RCIN_NAVIO_PCM_CS_A] = 1; // Disable Rx+Tx, Enable PCM block
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
@ -357,7 +357,7 @@ void LinuxRCInput_Navio::init_PCM()
|
||||
See BCM2835 documentation:
|
||||
http://www.raspberrypi.org/wp-content/uploads/2012/02/BCM2835-ARM-Peripherals.pdf
|
||||
*/
|
||||
void LinuxRCInput_Navio::init_DMA()
|
||||
void RCInput_Navio::init_DMA()
|
||||
{
|
||||
dma_reg[RCIN_NAVIO_DMA_CS | RCIN_NAVIO_DMA_CHANNEL << 8] = RCIN_NAVIO_DMA_RESET; //Reset DMA
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
@ -369,19 +369,19 @@ void LinuxRCInput_Navio::init_DMA()
|
||||
|
||||
|
||||
//We must stop DMA when the process is killed
|
||||
void LinuxRCInput_Navio::set_sigaction()
|
||||
void RCInput_Navio::set_sigaction()
|
||||
{
|
||||
for (int i = 0; i < 64; i++) {
|
||||
//catch all signals (like ctrl+c, ctrl+z, ...) to ensure DMA is disabled
|
||||
struct sigaction sa;
|
||||
memset(&sa, 0, sizeof(sa));
|
||||
sa.sa_handler = LinuxRCInput_Navio::termination_handler;
|
||||
sa.sa_handler = RCInput_Navio::termination_handler;
|
||||
sigaction(i, &sa, NULL);
|
||||
}
|
||||
}
|
||||
|
||||
//Initial setup of variables
|
||||
LinuxRCInput_Navio::LinuxRCInput_Navio():
|
||||
RCInput_Navio::RCInput_Navio():
|
||||
prev_tick(0),
|
||||
delta_time(0),
|
||||
curr_tick_inc(1000/RCIN_NAVIO_SAMPLE_FREQ),
|
||||
@ -392,7 +392,7 @@ LinuxRCInput_Navio::LinuxRCInput_Navio():
|
||||
last_signal(228),
|
||||
state(RCIN_NAVIO_INITIAL_STATE)
|
||||
{
|
||||
int version = LinuxUtilRPI::from(hal.util)->get_rpi_version();
|
||||
int version = UtilRPI::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"
|
||||
@ -400,26 +400,26 @@ LinuxRCInput_Navio::LinuxRCInput_Navio():
|
||||
con_blocks = new Memory_table(RCIN_NAVIO_BUFFER_LENGTH * 113, version);
|
||||
}
|
||||
|
||||
LinuxRCInput_Navio::~LinuxRCInput_Navio()
|
||||
RCInput_Navio::~RCInput_Navio()
|
||||
{
|
||||
delete circle_buffer;
|
||||
delete con_blocks;
|
||||
}
|
||||
|
||||
void LinuxRCInput_Navio::deinit()
|
||||
void RCInput_Navio::deinit()
|
||||
{
|
||||
stop_dma();
|
||||
}
|
||||
|
||||
//Initializing necessary registers
|
||||
void LinuxRCInput_Navio::init_registers()
|
||||
void RCInput_Navio::init_registers()
|
||||
{
|
||||
dma_reg = (uint32_t*)map_peripheral(dma_base, RCIN_NAVIO_DMA_LEN);
|
||||
pcm_reg = (uint32_t*)map_peripheral(pcm_base, RCIN_NAVIO_PCM_LEN);
|
||||
clk_reg = (uint32_t*)map_peripheral(clk_base, RCIN_NAVIO_CLK_LEN);
|
||||
}
|
||||
|
||||
void LinuxRCInput_Navio::init(void*)
|
||||
void RCInput_Navio::init(void*)
|
||||
{
|
||||
|
||||
init_registers();
|
||||
@ -448,7 +448,7 @@ void LinuxRCInput_Navio::init(void*)
|
||||
|
||||
|
||||
//Processing signal
|
||||
void LinuxRCInput_Navio::_timer_tick()
|
||||
void RCInput_Navio::_timer_tick()
|
||||
{
|
||||
int j;
|
||||
void* x;
|
||||
|
@ -45,8 +45,8 @@ typedef struct {
|
||||
} dma_cb_t;
|
||||
|
||||
class Memory_table {
|
||||
// Allow LinuxRCInput_Navio access to private members of Memory_table
|
||||
friend class Linux::LinuxRCInput_Navio;
|
||||
// Allow RCInput_Navio access to private members of Memory_table
|
||||
friend class Linux::RCInput_Navio;
|
||||
|
||||
private:
|
||||
void** _virt_pages;
|
||||
@ -74,13 +74,13 @@ public:
|
||||
};
|
||||
|
||||
|
||||
class Linux::LinuxRCInput_Navio : public Linux::LinuxRCInput
|
||||
class Linux::RCInput_Navio : public Linux::RCInput
|
||||
{
|
||||
public:
|
||||
void init(void*);
|
||||
void _timer_tick(void);
|
||||
LinuxRCInput_Navio();
|
||||
~LinuxRCInput_Navio();
|
||||
RCInput_Navio();
|
||||
~RCInput_Navio();
|
||||
|
||||
private:
|
||||
|
||||
|
@ -24,7 +24,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
void LinuxRCInput_PRU::init(void*)
|
||||
void RCInput_PRU::init(void*)
|
||||
{
|
||||
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC);
|
||||
if (mem_fd == -1) {
|
||||
@ -44,7 +44,7 @@ void LinuxRCInput_PRU::init(void*)
|
||||
/*
|
||||
called at 1kHz to check for new pulse capture data from the PRU
|
||||
*/
|
||||
void LinuxRCInput_PRU::_timer_tick()
|
||||
void RCInput_PRU::_timer_tick()
|
||||
{
|
||||
while (ring_buffer->ring_head != ring_buffer->ring_tail) {
|
||||
if (ring_buffer->ring_tail >= NUM_RING_ENTRIES) {
|
||||
|
@ -13,7 +13,7 @@
|
||||
// we use 300 ring buffer entries to guarantee that a full 25 byte
|
||||
// frame of 12 bits per byte
|
||||
|
||||
class Linux::LinuxRCInput_PRU : public Linux::LinuxRCInput
|
||||
class Linux::RCInput_PRU : public Linux::RCInput
|
||||
{
|
||||
public:
|
||||
void init(void*);
|
||||
|
@ -19,7 +19,7 @@ static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
void LinuxRCInput_Raspilot::init(void*)
|
||||
void RCInput_Raspilot::init(void*)
|
||||
{
|
||||
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
@ -31,10 +31,10 @@ void LinuxRCInput_Raspilot::init(void*)
|
||||
}
|
||||
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&LinuxRCInput_Raspilot::_poll_data, void));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&RCInput_Raspilot::_poll_data, void));
|
||||
}
|
||||
|
||||
void LinuxRCInput_Raspilot::_poll_data(void)
|
||||
void RCInput_Raspilot::_poll_data(void)
|
||||
{
|
||||
// Throttle read rate to 100hz maximum.
|
||||
if (hal.scheduler->micros() - _last_timer < 10000) {
|
||||
|
@ -5,7 +5,7 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "RCInput.h"
|
||||
|
||||
class Linux::LinuxRCInput_Raspilot : public Linux::LinuxRCInput
|
||||
class Linux::RCInput_Raspilot : public Linux::RCInput
|
||||
{
|
||||
public:
|
||||
void init(void*);
|
||||
|
@ -8,13 +8,13 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
LinuxRCInput_UDP::LinuxRCInput_UDP() :
|
||||
RCInput_UDP::RCInput_UDP() :
|
||||
_port(0),
|
||||
_last_buf_ts(0),
|
||||
_last_buf_seq(0)
|
||||
{}
|
||||
|
||||
void LinuxRCInput_UDP::init(void *)
|
||||
void RCInput_UDP::init(void *)
|
||||
{
|
||||
_port = RCINPUT_UDP_DEF_PORT;
|
||||
if(!_socket.bind("0.0.0.0", _port)) {
|
||||
@ -26,7 +26,7 @@ void LinuxRCInput_UDP::init(void *)
|
||||
return;
|
||||
}
|
||||
|
||||
void LinuxRCInput_UDP::_timer_tick(void)
|
||||
void RCInput_UDP::_timer_tick(void)
|
||||
{
|
||||
uint64_t delay;
|
||||
uint16_t seq_inc;
|
||||
|
@ -8,10 +8,10 @@
|
||||
|
||||
#define RCINPUT_UDP_DEF_PORT 777
|
||||
|
||||
class Linux::LinuxRCInput_UDP : public Linux::LinuxRCInput
|
||||
class Linux::RCInput_UDP : public Linux::RCInput
|
||||
{
|
||||
public:
|
||||
LinuxRCInput_UDP();
|
||||
RCInput_UDP();
|
||||
void init(void*);
|
||||
void _timer_tick(void);
|
||||
private:
|
||||
|
@ -21,7 +21,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
void LinuxRCInput_ZYNQ::init(void*)
|
||||
void RCInput_ZYNQ::init(void*)
|
||||
{
|
||||
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC);
|
||||
if (mem_fd == -1) {
|
||||
@ -37,7 +37,7 @@ void LinuxRCInput_ZYNQ::init(void*)
|
||||
/*
|
||||
called at 1kHz to check for new pulse capture data from the PL pulse timer
|
||||
*/
|
||||
void LinuxRCInput_ZYNQ::_timer_tick()
|
||||
void RCInput_ZYNQ::_timer_tick()
|
||||
{
|
||||
uint32_t v;
|
||||
|
||||
|
@ -12,7 +12,7 @@
|
||||
// FIXME A puppie dies when you hard code an address
|
||||
#define RCIN_ZYNQ_PULSE_INPUT_BASE 0x43c10000
|
||||
|
||||
class Linux::LinuxRCInput_ZYNQ : public Linux::LinuxRCInput
|
||||
class Linux::RCInput_ZYNQ : public Linux::RCInput
|
||||
{
|
||||
public:
|
||||
void init(void*);
|
||||
|
@ -33,7 +33,7 @@ static void catch_sigbus(int sig)
|
||||
{
|
||||
hal.scheduler->panic("RCOutputAioPRU.cpp:SIGBUS error gernerated\n");
|
||||
}
|
||||
void LinuxRCOutput_AioPRU::init(void* machtnicht)
|
||||
void RCOutput_AioPRU::init(void* machtnicht)
|
||||
{
|
||||
uint32_t mem_fd;
|
||||
uint32_t *iram;
|
||||
@ -64,7 +64,7 @@ void LinuxRCOutput_AioPRU::init(void* machtnicht)
|
||||
set_freq(0xFFFFFFFF, 50);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_AioPRU::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
void RCOutput_AioPRU::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
{
|
||||
uint8_t i;
|
||||
uint32_t tick = TICK_PER_S / freq_hz;
|
||||
@ -76,7 +76,7 @@ void LinuxRCOutput_AioPRU::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_AioPRU::get_freq(uint8_t ch)
|
||||
uint16_t RCOutput_AioPRU::get_freq(uint8_t ch)
|
||||
{
|
||||
uint16_t ret = 0;
|
||||
|
||||
@ -87,28 +87,28 @@ uint16_t LinuxRCOutput_AioPRU::get_freq(uint8_t ch)
|
||||
return ret;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_AioPRU::enable_ch(uint8_t ch)
|
||||
void RCOutput_AioPRU::enable_ch(uint8_t ch)
|
||||
{
|
||||
if(ch < PWM_CHAN_COUNT) {
|
||||
pwm->channelenable |= 1U << ch;
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxRCOutput_AioPRU::disable_ch(uint8_t ch)
|
||||
void RCOutput_AioPRU::disable_ch(uint8_t ch)
|
||||
{
|
||||
if(ch < PWM_CHAN_COUNT) {
|
||||
pwm->channelenable &= !(1U << ch);
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxRCOutput_AioPRU::write(uint8_t ch, uint16_t period_us)
|
||||
void RCOutput_AioPRU::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
if(ch < PWM_CHAN_COUNT) {
|
||||
pwm->channel[ch].time_high = TICK_PER_US * period_us;
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_AioPRU::read(uint8_t ch)
|
||||
uint16_t RCOutput_AioPRU::read(uint8_t ch)
|
||||
{
|
||||
uint16_t ret = 0;
|
||||
|
||||
@ -119,7 +119,7 @@ uint16_t LinuxRCOutput_AioPRU::read(uint8_t ch)
|
||||
return ret;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_AioPRU::read(uint16_t* period_us, uint8_t len)
|
||||
void RCOutput_AioPRU::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
|
@ -19,7 +19,7 @@
|
||||
#define RCOUT_PRUSS_IRAM_BASE 0x4a338000
|
||||
#define PWM_CHAN_COUNT 12
|
||||
|
||||
class Linux::LinuxRCOutput_AioPRU : public AP_HAL::RCOutput {
|
||||
class Linux::RCOutput_AioPRU : public AP_HAL::RCOutput {
|
||||
void init(void* machtnichts);
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
|
@ -91,7 +91,7 @@ using namespace Linux;
|
||||
|
||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
LinuxRCOutput_Bebop::LinuxRCOutput_Bebop():
|
||||
RCOutput_Bebop::RCOutput_Bebop():
|
||||
_i2c_sem(NULL),
|
||||
_min_pwm(BEBOP_BLDC_MIN_PERIOD_US),
|
||||
_max_pwm(BEBOP_BLDC_MAX_PERIOD_US),
|
||||
@ -102,7 +102,7 @@ LinuxRCOutput_Bebop::LinuxRCOutput_Bebop():
|
||||
memset(_rpm, 0, sizeof(_rpm));
|
||||
}
|
||||
|
||||
uint8_t LinuxRCOutput_Bebop::_checksum(uint8_t *data, unsigned int len)
|
||||
uint8_t RCOutput_Bebop::_checksum(uint8_t *data, unsigned int len)
|
||||
{
|
||||
uint8_t checksum = data[0];
|
||||
unsigned int i;
|
||||
@ -113,7 +113,7 @@ uint8_t LinuxRCOutput_Bebop::_checksum(uint8_t *data, unsigned int len)
|
||||
return checksum;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::_start_prop()
|
||||
void RCOutput_Bebop::_start_prop()
|
||||
{
|
||||
uint8_t data = BEBOP_BLDC_STARTPROP;
|
||||
|
||||
@ -126,7 +126,7 @@ void LinuxRCOutput_Bebop::_start_prop()
|
||||
_state = BEBOP_BLDC_STARTED;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::_set_ref_speed(uint16_t rpm[BEBOP_BLDC_MOTORS_NUM])
|
||||
void RCOutput_Bebop::_set_ref_speed(uint16_t rpm[BEBOP_BLDC_MOTORS_NUM])
|
||||
{
|
||||
struct bldc_ref_speed_data data;
|
||||
int i;
|
||||
@ -147,7 +147,7 @@ void LinuxRCOutput_Bebop::_set_ref_speed(uint16_t rpm[BEBOP_BLDC_MOTORS_NUM])
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
int LinuxRCOutput_Bebop::read_obs_data(BebopBLDC_ObsData &obs)
|
||||
int RCOutput_Bebop::read_obs_data(BebopBLDC_ObsData &obs)
|
||||
{
|
||||
struct bldc_obs_data data;
|
||||
int i;
|
||||
@ -183,7 +183,7 @@ int LinuxRCOutput_Bebop::read_obs_data(BebopBLDC_ObsData &obs)
|
||||
return 0;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::_toggle_gpio(uint8_t mask)
|
||||
void RCOutput_Bebop::_toggle_gpio(uint8_t mask)
|
||||
{
|
||||
if (!_i2c_sem->take(0))
|
||||
return;
|
||||
@ -193,7 +193,7 @@ void LinuxRCOutput_Bebop::_toggle_gpio(uint8_t mask)
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::_stop_prop()
|
||||
void RCOutput_Bebop::_stop_prop()
|
||||
{
|
||||
uint8_t data = BEBOP_BLDC_STOP_PROP;
|
||||
_state = BEBOP_BLDC_STOPPED;
|
||||
@ -206,7 +206,7 @@ void LinuxRCOutput_Bebop::_stop_prop()
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::_clear_error()
|
||||
void RCOutput_Bebop::_clear_error()
|
||||
{
|
||||
uint8_t data = BEBOP_BLDC_CLEAR_ERROR;
|
||||
|
||||
@ -218,7 +218,7 @@ void LinuxRCOutput_Bebop::_clear_error()
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::_play_sound(uint8_t sound)
|
||||
void RCOutput_Bebop::_play_sound(uint8_t sound)
|
||||
{
|
||||
if (!_i2c_sem->take(0))
|
||||
return;
|
||||
@ -228,7 +228,7 @@ void LinuxRCOutput_Bebop::_play_sound(uint8_t sound)
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_Bebop::_period_us_to_rpm(uint16_t period_us)
|
||||
uint16_t RCOutput_Bebop::_period_us_to_rpm(uint16_t period_us)
|
||||
{
|
||||
float period_us_fl = period_us;
|
||||
|
||||
@ -238,7 +238,7 @@ uint16_t LinuxRCOutput_Bebop::_period_us_to_rpm(uint16_t period_us)
|
||||
return (uint16_t)rpm_fl;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::init(void* dummy)
|
||||
void RCOutput_Bebop::init(void* dummy)
|
||||
{
|
||||
int ret=0;
|
||||
struct sched_param param = { .sched_priority = RCOUT_BEBOP_RTPRIO };
|
||||
@ -293,26 +293,26 @@ exit:
|
||||
return;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
void RCOutput_Bebop::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
{
|
||||
_frequency = freq_hz;
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_Bebop::get_freq(uint8_t ch)
|
||||
uint16_t RCOutput_Bebop::get_freq(uint8_t ch)
|
||||
{
|
||||
return _frequency;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::enable_ch(uint8_t ch)
|
||||
void RCOutput_Bebop::enable_ch(uint8_t ch)
|
||||
{
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::disable_ch(uint8_t ch)
|
||||
void RCOutput_Bebop::disable_ch(uint8_t ch)
|
||||
{
|
||||
_stop_prop();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::write(uint8_t ch, uint16_t period_us)
|
||||
void RCOutput_Bebop::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
if (ch >= BEBOP_BLDC_MOTORS_NUM)
|
||||
return;
|
||||
@ -323,12 +323,12 @@ void LinuxRCOutput_Bebop::write(uint8_t ch, uint16_t period_us)
|
||||
push();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::cork()
|
||||
void RCOutput_Bebop::cork()
|
||||
{
|
||||
_corking = true;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::push()
|
||||
void RCOutput_Bebop::push()
|
||||
{
|
||||
_corking = false;
|
||||
pthread_mutex_lock(&_mutex);
|
||||
@ -338,7 +338,7 @@ void LinuxRCOutput_Bebop::push()
|
||||
memset(_request_period_us, 0 ,sizeof(_request_period_us));
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_Bebop::read(uint8_t ch)
|
||||
uint16_t RCOutput_Bebop::read(uint8_t ch)
|
||||
{
|
||||
if (ch < BEBOP_BLDC_MOTORS_NUM) {
|
||||
return _period_us[ch];
|
||||
@ -347,27 +347,27 @@ uint16_t LinuxRCOutput_Bebop::read(uint8_t ch)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::read(uint16_t* period_us, uint8_t len)
|
||||
void RCOutput_Bebop::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
for (int i = 0; i < len; i++)
|
||||
period_us[i] = read(0 + i);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
|
||||
void RCOutput_Bebop::set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
|
||||
{
|
||||
_min_pwm = min_pwm;
|
||||
_max_pwm = max_pwm;
|
||||
}
|
||||
|
||||
/* Separate thread to handle the Bebop motors controller */
|
||||
void* LinuxRCOutput_Bebop::_control_thread(void *arg) {
|
||||
LinuxRCOutput_Bebop* rcout = (LinuxRCOutput_Bebop *) arg;
|
||||
void* RCOutput_Bebop::_control_thread(void *arg) {
|
||||
RCOutput_Bebop* rcout = (RCOutput_Bebop *) arg;
|
||||
|
||||
rcout->_run_rcout();
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Bebop::_run_rcout()
|
||||
void RCOutput_Bebop::_run_rcout()
|
||||
{
|
||||
uint16_t current_period_us[BEBOP_BLDC_MOTORS_NUM];
|
||||
uint8_t i;
|
||||
|
@ -47,12 +47,12 @@ public:
|
||||
uint8_t temperature;
|
||||
};
|
||||
|
||||
class Linux::LinuxRCOutput_Bebop : public AP_HAL::RCOutput {
|
||||
class Linux::RCOutput_Bebop : public AP_HAL::RCOutput {
|
||||
public:
|
||||
LinuxRCOutput_Bebop();
|
||||
RCOutput_Bebop();
|
||||
|
||||
static LinuxRCOutput_Bebop *from(AP_HAL::RCOutput *rcout) {
|
||||
return static_cast<LinuxRCOutput_Bebop*>(rcout);
|
||||
static RCOutput_Bebop *from(AP_HAL::RCOutput *rcout) {
|
||||
return static_cast<RCOutput_Bebop*>(rcout);
|
||||
}
|
||||
|
||||
void init(void* dummy);
|
||||
|
@ -56,7 +56,7 @@ using namespace Linux;
|
||||
|
||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
LinuxRCOutput_PCA9685::LinuxRCOutput_PCA9685(uint8_t addr,
|
||||
RCOutput_PCA9685::RCOutput_PCA9685(uint8_t addr,
|
||||
bool external_clock,
|
||||
uint8_t channel_offset,
|
||||
int16_t oe_pin_number) :
|
||||
@ -75,12 +75,12 @@ LinuxRCOutput_PCA9685::LinuxRCOutput_PCA9685(uint8_t addr,
|
||||
_osc_clock = PCA9685_INTERNAL_CLOCK;
|
||||
}
|
||||
|
||||
LinuxRCOutput_PCA9685::~LinuxRCOutput_PCA9685()
|
||||
RCOutput_PCA9685::~RCOutput_PCA9685()
|
||||
{
|
||||
delete [] _pulses_buffer;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::init(void* machtnicht)
|
||||
void RCOutput_PCA9685::init(void* machtnicht)
|
||||
{
|
||||
_i2c_sem = hal.i2c->get_semaphore();
|
||||
if (_i2c_sem == NULL) {
|
||||
@ -102,7 +102,7 @@ void LinuxRCOutput_PCA9685::init(void* machtnicht)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::reset_all_channels()
|
||||
void RCOutput_PCA9685::reset_all_channels()
|
||||
{
|
||||
if (!_i2c_sem->take(10)) {
|
||||
return;
|
||||
@ -117,7 +117,7 @@ void LinuxRCOutput_PCA9685::reset_all_channels()
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
void RCOutput_PCA9685::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
{
|
||||
|
||||
/* Correctly finish last pulses */
|
||||
@ -160,22 +160,22 @@ void LinuxRCOutput_PCA9685::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_PCA9685::get_freq(uint8_t ch)
|
||||
uint16_t RCOutput_PCA9685::get_freq(uint8_t ch)
|
||||
{
|
||||
return _frequency;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::enable_ch(uint8_t ch)
|
||||
void RCOutput_PCA9685::enable_ch(uint8_t ch)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::disable_ch(uint8_t ch)
|
||||
void RCOutput_PCA9685::disable_ch(uint8_t ch)
|
||||
{
|
||||
write(ch, 0);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::write(uint8_t ch, uint16_t period_us)
|
||||
void RCOutput_PCA9685::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
if (ch >= (PWM_CHAN_COUNT - _channel_offset)) {
|
||||
return;
|
||||
@ -188,12 +188,12 @@ void LinuxRCOutput_PCA9685::write(uint8_t ch, uint16_t period_us)
|
||||
push();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::cork()
|
||||
void RCOutput_PCA9685::cork()
|
||||
{
|
||||
_corking = true;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::push()
|
||||
void RCOutput_PCA9685::push()
|
||||
{
|
||||
_corking = false;
|
||||
|
||||
@ -239,12 +239,12 @@ void LinuxRCOutput_PCA9685::push()
|
||||
_pending_write_mask = 0;
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_PCA9685::read(uint8_t ch)
|
||||
uint16_t RCOutput_PCA9685::read(uint8_t ch)
|
||||
{
|
||||
return _pulses_buffer[ch];
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PCA9685::read(uint16_t* period_us, uint8_t len)
|
||||
void RCOutput_PCA9685::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
for (int i = 0; i < len; i++)
|
||||
period_us[i] = read(0 + i);
|
||||
|
@ -8,11 +8,11 @@
|
||||
#define PCA9685_SECONDARY_ADDRESS 0x41
|
||||
#define PCA9685_TERTIARY_ADDRESS 0x42
|
||||
|
||||
class Linux::LinuxRCOutput_PCA9685 : public AP_HAL::RCOutput {
|
||||
class Linux::RCOutput_PCA9685 : public AP_HAL::RCOutput {
|
||||
public:
|
||||
LinuxRCOutput_PCA9685(uint8_t addr, bool external_clock, uint8_t channel_offset,
|
||||
RCOutput_PCA9685(uint8_t addr, bool external_clock, uint8_t channel_offset,
|
||||
int16_t oe_pin_number);
|
||||
~LinuxRCOutput_PCA9685();
|
||||
~RCOutput_PCA9685();
|
||||
void init(void* machtnichts);
|
||||
void reset_all_channels();
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
|
@ -29,7 +29,7 @@ static void catch_sigbus(int sig)
|
||||
{
|
||||
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");
|
||||
}
|
||||
void LinuxRCOutput_PRU::init(void* machtnicht)
|
||||
void RCOutput_PRU::init(void* machtnicht)
|
||||
{
|
||||
uint32_t mem_fd;
|
||||
signal(SIGBUS,catch_sigbus);
|
||||
@ -43,7 +43,7 @@ void LinuxRCOutput_PRU::init(void* machtnicht)
|
||||
set_freq(0xFFFFFFFF, 50);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PRU::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
|
||||
void RCOutput_PRU::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
|
||||
{
|
||||
uint8_t i;
|
||||
unsigned long tick=TICK_PER_S/(unsigned long)freq_hz;
|
||||
@ -55,32 +55,32 @@ void LinuxRCOutput_PRU::set_freq(uint32_t chmask, uint16_t freq_hz) /
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_PRU::get_freq(uint8_t ch)
|
||||
uint16_t RCOutput_PRU::get_freq(uint8_t ch)
|
||||
{
|
||||
return TICK_PER_S/sharedMem_cmd->periodhi[chan_pru_map[ch]][0];
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PRU::enable_ch(uint8_t ch)
|
||||
void RCOutput_PRU::enable_ch(uint8_t ch)
|
||||
{
|
||||
sharedMem_cmd->enmask |= 1U<<chan_pru_map[ch];
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PRU::disable_ch(uint8_t ch)
|
||||
void RCOutput_PRU::disable_ch(uint8_t ch)
|
||||
{
|
||||
sharedMem_cmd->enmask &= !(1U<<chan_pru_map[ch]);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PRU::write(uint8_t ch, uint16_t period_us)
|
||||
void RCOutput_PRU::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
sharedMem_cmd->periodhi[chan_pru_map[ch]][1] = TICK_PER_US*period_us;
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_PRU::read(uint8_t ch)
|
||||
uint16_t RCOutput_PRU::read(uint8_t ch)
|
||||
{
|
||||
return (sharedMem_cmd->hilo_read[chan_pru_map[ch]][1]/TICK_PER_US);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_PRU::read(uint16_t* period_us, uint8_t len)
|
||||
void RCOutput_PRU::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
uint8_t i;
|
||||
if(len>PWM_CHAN_COUNT){
|
||||
|
@ -15,7 +15,7 @@
|
||||
#define PWM_CMD_CLR 5 /* clr a pwm output explicitly */
|
||||
#define PWM_CMD_TEST 6 /* various crap */
|
||||
|
||||
class Linux::LinuxRCOutput_PRU : public AP_HAL::RCOutput {
|
||||
class Linux::RCOutput_PRU : public AP_HAL::RCOutput {
|
||||
void init(void* machtnichts);
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
|
@ -22,7 +22,7 @@ using namespace Linux;
|
||||
|
||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
void LinuxRCOutput_Raspilot::init(void* machtnicht)
|
||||
void RCOutput_Raspilot::init(void* machtnicht)
|
||||
{
|
||||
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
@ -33,10 +33,10 @@ void LinuxRCOutput_Raspilot::init(void* machtnicht)
|
||||
return; // never reached
|
||||
}
|
||||
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&LinuxRCOutput_Raspilot::_update, void));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&RCOutput_Raspilot::_update, void));
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Raspilot::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
void RCOutput_Raspilot::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
{
|
||||
if (!_spi_sem->take(10)) {
|
||||
return;
|
||||
@ -57,22 +57,22 @@ void LinuxRCOutput_Raspilot::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
_spi_sem->give();
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_Raspilot::get_freq(uint8_t ch)
|
||||
uint16_t RCOutput_Raspilot::get_freq(uint8_t ch)
|
||||
{
|
||||
return _frequency;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Raspilot::enable_ch(uint8_t ch)
|
||||
void RCOutput_Raspilot::enable_ch(uint8_t ch)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Raspilot::disable_ch(uint8_t ch)
|
||||
void RCOutput_Raspilot::disable_ch(uint8_t ch)
|
||||
{
|
||||
write(ch, 0);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Raspilot::write(uint8_t ch, uint16_t period_us)
|
||||
void RCOutput_Raspilot::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
if(ch >= PWM_CHAN_COUNT){
|
||||
return;
|
||||
@ -81,7 +81,7 @@ void LinuxRCOutput_Raspilot::write(uint8_t ch, uint16_t period_us)
|
||||
_period_us[ch] = period_us;
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_Raspilot::read(uint8_t ch)
|
||||
uint16_t RCOutput_Raspilot::read(uint8_t ch)
|
||||
{
|
||||
if(ch >= PWM_CHAN_COUNT){
|
||||
return 0;
|
||||
@ -90,13 +90,13 @@ uint16_t LinuxRCOutput_Raspilot::read(uint8_t ch)
|
||||
return _period_us[ch];
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Raspilot::read(uint16_t* period_us, uint8_t len)
|
||||
void RCOutput_Raspilot::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
for (int i = 0; i < len; i++)
|
||||
period_us[i] = read(0 + i);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Raspilot::_update(void)
|
||||
void RCOutput_Raspilot::_update(void)
|
||||
{
|
||||
int i;
|
||||
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
class Linux::LinuxRCOutput_Raspilot : public AP_HAL::RCOutput {
|
||||
class Linux::RCOutput_Raspilot : public AP_HAL::RCOutput {
|
||||
void init(void* machtnichts);
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
|
@ -25,7 +25,7 @@ static void catch_sigbus(int sig)
|
||||
{
|
||||
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");
|
||||
}
|
||||
void LinuxRCOutput_ZYNQ::init(void* machtnicht)
|
||||
void RCOutput_ZYNQ::init(void* machtnicht)
|
||||
{
|
||||
uint32_t mem_fd;
|
||||
signal(SIGBUS,catch_sigbus);
|
||||
@ -39,7 +39,7 @@ void LinuxRCOutput_ZYNQ::init(void* machtnicht)
|
||||
set_freq(0xFFFFFFFF, 50);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_ZYNQ::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
|
||||
void RCOutput_ZYNQ::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
|
||||
{
|
||||
uint8_t i;
|
||||
unsigned long tick=TICK_PER_S/(unsigned long)freq_hz;
|
||||
@ -51,32 +51,32 @@ void LinuxRCOutput_ZYNQ::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_ZYNQ::get_freq(uint8_t ch)
|
||||
uint16_t RCOutput_ZYNQ::get_freq(uint8_t ch)
|
||||
{
|
||||
return TICK_PER_S/sharedMem_cmd->periodhi[ch].period;;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_ZYNQ::enable_ch(uint8_t ch)
|
||||
void RCOutput_ZYNQ::enable_ch(uint8_t ch)
|
||||
{
|
||||
// sharedMem_cmd->enmask |= 1U<<chan_pru_map[ch];
|
||||
}
|
||||
|
||||
void LinuxRCOutput_ZYNQ::disable_ch(uint8_t ch)
|
||||
void RCOutput_ZYNQ::disable_ch(uint8_t ch)
|
||||
{
|
||||
// sharedMem_cmd->enmask &= !(1U<<chan_pru_map[ch]);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_ZYNQ::write(uint8_t ch, uint16_t period_us)
|
||||
void RCOutput_ZYNQ::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
sharedMem_cmd->periodhi[ch].hi = TICK_PER_US*period_us;
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_ZYNQ::read(uint8_t ch)
|
||||
uint16_t RCOutput_ZYNQ::read(uint8_t ch)
|
||||
{
|
||||
return (sharedMem_cmd->periodhi[ch].hi/TICK_PER_US);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_ZYNQ::read(uint16_t* period_us, uint8_t len)
|
||||
void RCOutput_ZYNQ::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
uint8_t i;
|
||||
if(len>PWM_CHAN_COUNT){
|
||||
|
@ -14,7 +14,7 @@
|
||||
#define PWM_CMD_TEST 6 /* various crap */
|
||||
|
||||
|
||||
class Linux::LinuxRCOutput_ZYNQ : public AP_HAL::RCOutput {
|
||||
class Linux::RCOutput_ZYNQ : public AP_HAL::RCOutput {
|
||||
void init(void* machtnichts);
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
|
@ -27,8 +27,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
LinuxRPIOUARTDriver::LinuxRPIOUARTDriver() :
|
||||
LinuxUARTDriver(false),
|
||||
RPIOUARTDriver::RPIOUARTDriver() :
|
||||
UARTDriver(false),
|
||||
_spi(NULL),
|
||||
_spi_sem(NULL),
|
||||
_last_update_timestamp(0),
|
||||
@ -40,27 +40,27 @@ LinuxRPIOUARTDriver::LinuxRPIOUARTDriver() :
|
||||
_writebuf = NULL;
|
||||
}
|
||||
|
||||
bool LinuxRPIOUARTDriver::sem_take_nonblocking()
|
||||
bool RPIOUARTDriver::sem_take_nonblocking()
|
||||
{
|
||||
return _spi_sem->take_nonblocking();
|
||||
}
|
||||
|
||||
void LinuxRPIOUARTDriver::sem_give()
|
||||
void RPIOUARTDriver::sem_give()
|
||||
{
|
||||
_spi_sem->give();
|
||||
}
|
||||
|
||||
bool LinuxRPIOUARTDriver::isExternal()
|
||||
bool RPIOUARTDriver::isExternal()
|
||||
{
|
||||
return _external;
|
||||
}
|
||||
|
||||
void LinuxRPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
void RPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
{
|
||||
//hal.console->printf("[RPIOUARTDriver]: begin \n");
|
||||
|
||||
if (device_path != NULL) {
|
||||
LinuxUARTDriver::begin(b,rxS,txS);
|
||||
UARTDriver::begin(b,rxS,txS);
|
||||
if ( is_initialized()) {
|
||||
_external = true;
|
||||
return;
|
||||
@ -130,28 +130,28 @@ void LinuxRPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
|
||||
}
|
||||
|
||||
int LinuxRPIOUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
||||
int RPIOUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
||||
{
|
||||
if (_external) {
|
||||
return LinuxUARTDriver::_write_fd(buf, n);
|
||||
return UARTDriver::_write_fd(buf, n);
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
int LinuxRPIOUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||
int RPIOUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||
{
|
||||
if (_external) {
|
||||
return LinuxUARTDriver::_read_fd(buf, n);
|
||||
return UARTDriver::_read_fd(buf, n);
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
void LinuxRPIOUARTDriver::_timer_tick(void)
|
||||
void RPIOUARTDriver::_timer_tick(void)
|
||||
{
|
||||
if (_external) {
|
||||
LinuxUARTDriver::_timer_tick();
|
||||
UARTDriver::_timer_tick();
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -6,12 +6,12 @@
|
||||
#include "UARTDriver.h"
|
||||
|
||||
|
||||
class Linux::LinuxRPIOUARTDriver : public Linux::LinuxUARTDriver {
|
||||
class Linux::RPIOUARTDriver : public Linux::UARTDriver {
|
||||
public:
|
||||
LinuxRPIOUARTDriver();
|
||||
RPIOUARTDriver();
|
||||
|
||||
static LinuxRPIOUARTDriver *from(AP_HAL::UARTDriver *uart) {
|
||||
return static_cast<LinuxRPIOUARTDriver*>(uart);
|
||||
static RPIOUARTDriver *from(AP_HAL::UARTDriver *uart) {
|
||||
return static_cast<RPIOUARTDriver*>(uart);
|
||||
}
|
||||
|
||||
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
||||
|
@ -24,49 +24,49 @@ extern const AP_HAL::HAL& hal;
|
||||
#define KHZ (1000U)
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[] = {
|
||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
||||
// different SPI tables per board subtype
|
||||
LinuxSPIDeviceDriver(1, 0, AP_HAL::SPIDevice_LSM9DS0_AM, SPI_MODE_3, 8, BBB_P9_17, 10*MHZ,10*MHZ),
|
||||
LinuxSPIDeviceDriver(1, 0, AP_HAL::SPIDevice_LSM9DS0_G, SPI_MODE_3, 8, BBB_P8_9, 10*MHZ,10*MHZ),
|
||||
LinuxSPIDeviceDriver(2, 0, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, BBB_P9_42, 10*MHZ,10*MHZ),
|
||||
LinuxSPIDeviceDriver(2, 0, AP_HAL::SPIDevice_MPU6000, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ),
|
||||
SPIDeviceDriver(1, 0, AP_HAL::SPIDevice_LSM9DS0_AM, SPI_MODE_3, 8, BBB_P9_17, 10*MHZ,10*MHZ),
|
||||
SPIDeviceDriver(1, 0, AP_HAL::SPIDevice_LSM9DS0_G, SPI_MODE_3, 8, BBB_P8_9, 10*MHZ,10*MHZ),
|
||||
SPIDeviceDriver(2, 0, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, BBB_P9_42, 10*MHZ,10*MHZ),
|
||||
SPIDeviceDriver(2, 0, AP_HAL::SPIDevice_MPU6000, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ),
|
||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||
LinuxSPIDeviceDriver(2, 0, AP_HAL::SPIDevice_MPU9250, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ),
|
||||
LinuxSPIDeviceDriver(2, 0, AP_HAL::SPIDevice_Dataflash, SPI_MODE_3, 8, BBB_P8_12, 6*MHZ, 6*MHZ),
|
||||
SPIDeviceDriver(2, 0, AP_HAL::SPIDevice_MPU9250, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ),
|
||||
SPIDeviceDriver(2, 0, AP_HAL::SPIDevice_Dataflash, SPI_MODE_3, 8, BBB_P8_12, 6*MHZ, 6*MHZ),
|
||||
};
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[] = {
|
||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||
LinuxSPIDeviceDriver(0, 1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_Ublox, SPI_MODE_0, 8, SPI_CS_KERNEL, 250*KHZ, 5*MHZ),
|
||||
SPIDeviceDriver(0, 1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_Ublox, SPI_MODE_0, 8, SPI_CS_KERNEL, 250*KHZ, 5*MHZ),
|
||||
};
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[] = {
|
||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||
LinuxSPIDeviceDriver(2, 0, AP_HAL::SPIDevice_MPU9250, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||
LinuxSPIDeviceDriver(2, 1, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, SPI_CS_KERNEL, 10*MHZ,10*MHZ),
|
||||
SPIDeviceDriver(2, 0, AP_HAL::SPIDevice_MPU9250, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||
SPIDeviceDriver(2, 1, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, SPI_CS_KERNEL, 10*MHZ,10*MHZ),
|
||||
};
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[] = {
|
||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_MPU6000, SPI_MODE_3, 8, RPI_GPIO_25, 1*MHZ, 8*MHZ),
|
||||
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, RPI_GPIO_23, 1*MHZ, 8*MHZ),
|
||||
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_L3GD20, SPI_MODE_3, 8, RPI_GPIO_12, 1*MHZ, 8*MHZ),
|
||||
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_LSM303D, SPI_MODE_3, 8, RPI_GPIO_22, 1*MHZ, 8*MHZ),
|
||||
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_Dataflash, SPI_MODE_3, 8, RPI_GPIO_5, 1*MHZ, 8*MHZ),
|
||||
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_RASPIO, SPI_MODE_3, 8, RPI_GPIO_7, 8*MHZ, 8*MHZ),
|
||||
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_MPU6000, SPI_MODE_3, 8, RPI_GPIO_25, 1*MHZ, 8*MHZ),
|
||||
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, RPI_GPIO_23, 1*MHZ, 8*MHZ),
|
||||
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_L3GD20, SPI_MODE_3, 8, RPI_GPIO_12, 1*MHZ, 8*MHZ),
|
||||
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_LSM303D, SPI_MODE_3, 8, RPI_GPIO_22, 1*MHZ, 8*MHZ),
|
||||
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_Dataflash, SPI_MODE_3, 8, RPI_GPIO_5, 1*MHZ, 8*MHZ),
|
||||
SPIDeviceDriver(0, 0, AP_HAL::SPIDevice_RASPIO, SPI_MODE_3, 8, RPI_GPIO_7, 8*MHZ, 8*MHZ),
|
||||
};
|
||||
#else
|
||||
// empty device table
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[0];
|
||||
SPIDeviceDriver SPIDeviceManager::_device[0];
|
||||
#endif
|
||||
|
||||
#define LINUX_SPI_DEVICE_NUM_DEVICES ARRAY_SIZE(LinuxSPIDeviceManager::_device)
|
||||
#define LINUX_SPI_DEVICE_NUM_DEVICES ARRAY_SIZE(SPIDeviceManager::_device)
|
||||
|
||||
// have a separate semaphore per bus
|
||||
LinuxSemaphore LinuxSPIDeviceManager::_semaphore[LINUX_SPI_MAX_BUSES];
|
||||
Semaphore SPIDeviceManager::_semaphore[LINUX_SPI_MAX_BUSES];
|
||||
|
||||
LinuxSPIDeviceDriver::LinuxSPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed):
|
||||
SPIDeviceDriver::SPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed):
|
||||
_bus(bus),
|
||||
_subdev(subdev),
|
||||
_type(type),
|
||||
@ -80,7 +80,7 @@ LinuxSPIDeviceDriver::LinuxSPIDeviceDriver(uint16_t bus, uint16_t subdev, enum A
|
||||
{
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceDriver::init()
|
||||
void SPIDeviceDriver::init()
|
||||
{
|
||||
// Init the CS
|
||||
if(_cs_pin != SPI_CS_KERNEL) {
|
||||
@ -95,17 +95,17 @@ void LinuxSPIDeviceDriver::init()
|
||||
}
|
||||
}
|
||||
|
||||
AP_HAL::Semaphore* LinuxSPIDeviceDriver::get_semaphore()
|
||||
AP_HAL::Semaphore* SPIDeviceDriver::get_semaphore()
|
||||
{
|
||||
return LinuxSPIDeviceManager::get_semaphore(_bus);
|
||||
return SPIDeviceManager::get_semaphore(_bus);
|
||||
}
|
||||
|
||||
bool LinuxSPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
bool SPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
{
|
||||
return LinuxSPIDeviceManager::transaction(*this, tx, rx, len);
|
||||
return SPIDeviceManager::transaction(*this, tx, rx, len);
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceDriver::set_bus_speed(enum bus_speed speed)
|
||||
void SPIDeviceDriver::set_bus_speed(enum bus_speed speed)
|
||||
{
|
||||
if (speed == SPI_SPEED_LOW) {
|
||||
_speed = _lowspeed;
|
||||
@ -114,29 +114,29 @@ void LinuxSPIDeviceDriver::set_bus_speed(enum bus_speed speed)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceDriver::cs_assert()
|
||||
void SPIDeviceDriver::cs_assert()
|
||||
{
|
||||
LinuxSPIDeviceManager::cs_assert(_type);
|
||||
SPIDeviceManager::cs_assert(_type);
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceDriver::cs_release()
|
||||
void SPIDeviceDriver::cs_release()
|
||||
{
|
||||
LinuxSPIDeviceManager::cs_release(_type);
|
||||
SPIDeviceManager::cs_release(_type);
|
||||
}
|
||||
|
||||
uint8_t LinuxSPIDeviceDriver::transfer(uint8_t data)
|
||||
uint8_t SPIDeviceDriver::transfer(uint8_t data)
|
||||
{
|
||||
uint8_t v = 0;
|
||||
transaction(&data, &v, 1);
|
||||
return v;
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceDriver::transfer(const uint8_t *data, uint16_t len)
|
||||
void SPIDeviceDriver::transfer(const uint8_t *data, uint16_t len)
|
||||
{
|
||||
transaction(data, NULL, len);
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceManager::init(void *)
|
||||
void SPIDeviceManager::init(void *)
|
||||
{
|
||||
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
||||
if (_device[i]._bus >= LINUX_SPI_MAX_BUSES) {
|
||||
@ -158,7 +158,7 @@ void LinuxSPIDeviceManager::init(void *)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceManager::cs_assert(enum AP_HAL::SPIDevice type)
|
||||
void SPIDeviceManager::cs_assert(enum AP_HAL::SPIDevice type)
|
||||
{
|
||||
uint16_t bus = 0, i;
|
||||
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
||||
@ -194,7 +194,7 @@ void LinuxSPIDeviceManager::cs_assert(enum AP_HAL::SPIDevice type)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceManager::cs_release(enum AP_HAL::SPIDevice type)
|
||||
void SPIDeviceManager::cs_release(enum AP_HAL::SPIDevice type)
|
||||
{
|
||||
uint16_t bus = 0, i;
|
||||
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
||||
@ -220,7 +220,7 @@ void LinuxSPIDeviceManager::cs_release(enum AP_HAL::SPIDevice type)
|
||||
}
|
||||
}
|
||||
|
||||
bool LinuxSPIDeviceManager::transaction(LinuxSPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
bool SPIDeviceManager::transaction(SPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
{
|
||||
int r;
|
||||
// we set the mode before we assert the CS line so that the bus is
|
||||
@ -261,7 +261,7 @@ bool LinuxSPIDeviceManager::transaction(LinuxSPIDeviceDriver &driver, const uint
|
||||
/*
|
||||
return a SPIDeviceDriver for a particular device
|
||||
*/
|
||||
AP_HAL::SPIDeviceDriver *LinuxSPIDeviceManager::device(enum AP_HAL::SPIDevice dev, uint8_t index)
|
||||
AP_HAL::SPIDeviceDriver *SPIDeviceManager::device(enum AP_HAL::SPIDevice dev, uint8_t index)
|
||||
{
|
||||
uint8_t count = 0;
|
||||
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
||||
@ -279,7 +279,7 @@ AP_HAL::SPIDeviceDriver *LinuxSPIDeviceManager::device(enum AP_HAL::SPIDevice de
|
||||
/*
|
||||
return the bus specific semaphore
|
||||
*/
|
||||
AP_HAL::Semaphore *LinuxSPIDeviceManager::get_semaphore(uint16_t bus)
|
||||
AP_HAL::Semaphore *SPIDeviceManager::get_semaphore(uint16_t bus)
|
||||
{
|
||||
return &_semaphore[bus];
|
||||
}
|
||||
|
@ -15,10 +15,10 @@
|
||||
// Fake CS pin to indicate in-kernel handling
|
||||
#define SPI_CS_KERNEL -1
|
||||
|
||||
class Linux::LinuxSPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
|
||||
class Linux::SPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
|
||||
public:
|
||||
friend class Linux::LinuxSPIDeviceManager;
|
||||
LinuxSPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
|
||||
friend class Linux::SPIDeviceManager;
|
||||
SPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
|
||||
void init();
|
||||
AP_HAL::Semaphore *get_semaphore();
|
||||
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
@ -46,7 +46,7 @@ private:
|
||||
int _fd; // Per-device FD.
|
||||
};
|
||||
|
||||
class Linux::LinuxSPIDeviceManager : public AP_HAL::SPIDeviceManager {
|
||||
class Linux::SPIDeviceManager : public AP_HAL::SPIDeviceManager {
|
||||
public:
|
||||
void init(void *);
|
||||
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index = 0);
|
||||
@ -55,11 +55,11 @@ public:
|
||||
|
||||
static void cs_assert(enum AP_HAL::SPIDevice type);
|
||||
static void cs_release(enum AP_HAL::SPIDevice type);
|
||||
static bool transaction(LinuxSPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
static bool transaction(SPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
|
||||
private:
|
||||
static LinuxSPIDeviceDriver _device[];
|
||||
static LinuxSemaphore _semaphore[LINUX_SPI_MAX_BUSES];
|
||||
static SPIDeviceDriver _device[];
|
||||
static Semaphore _semaphore[LINUX_SPI_MAX_BUSES];
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_LINUX_SPIDRIVER_H__
|
||||
|
@ -23,8 +23,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
LinuxSPIUARTDriver::LinuxSPIUARTDriver() :
|
||||
LinuxUARTDriver(false),
|
||||
SPIUARTDriver::SPIUARTDriver() :
|
||||
UARTDriver(false),
|
||||
_spi(NULL),
|
||||
_spi_sem(NULL),
|
||||
_last_update_timestamp(0),
|
||||
@ -35,20 +35,20 @@ LinuxSPIUARTDriver::LinuxSPIUARTDriver() :
|
||||
_writebuf = NULL;
|
||||
}
|
||||
|
||||
bool LinuxSPIUARTDriver::sem_take_nonblocking()
|
||||
bool SPIUARTDriver::sem_take_nonblocking()
|
||||
{
|
||||
return _spi_sem->take_nonblocking();
|
||||
}
|
||||
|
||||
void LinuxSPIUARTDriver::sem_give()
|
||||
void SPIUARTDriver::sem_give()
|
||||
{
|
||||
_spi_sem->give();
|
||||
}
|
||||
|
||||
void LinuxSPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
{
|
||||
if (device_path != NULL) {
|
||||
LinuxUARTDriver::begin(b,rxS,txS);
|
||||
UARTDriver::begin(b,rxS,txS);
|
||||
if ( is_initialized()) {
|
||||
_external = true;
|
||||
return;
|
||||
@ -129,10 +129,10 @@ void LinuxSPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
_initialised = true;
|
||||
}
|
||||
|
||||
int LinuxSPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
|
||||
int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
|
||||
{
|
||||
if (_external) {
|
||||
return LinuxUARTDriver::_write_fd(buf,size);
|
||||
return UARTDriver::_write_fd(buf,size);
|
||||
}
|
||||
|
||||
if (!sem_take_nonblocking()) {
|
||||
@ -150,7 +150,7 @@ int LinuxSPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
|
||||
/* Since all SPI-transactions are transfers we need update
|
||||
* the _readbuf. I do believe there is a way to encapsulate
|
||||
* this operation since it's the same as in the
|
||||
* LinuxUARTDriver::write().
|
||||
* UARTDriver::write().
|
||||
*/
|
||||
|
||||
uint8_t *buffer = _buffer;
|
||||
@ -194,10 +194,10 @@ int LinuxSPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
|
||||
}
|
||||
|
||||
static const uint8_t ff_stub[300] = {0xff};
|
||||
int LinuxSPIUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||
int SPIUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||
{
|
||||
if (_external) {
|
||||
return LinuxUARTDriver::_read_fd(buf, n);
|
||||
return UARTDriver::_read_fd(buf, n);
|
||||
}
|
||||
|
||||
if (!sem_take_nonblocking()) {
|
||||
@ -223,10 +223,10 @@ int LinuxSPIUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||
return n;
|
||||
}
|
||||
|
||||
void LinuxSPIUARTDriver::_timer_tick(void)
|
||||
void SPIUARTDriver::_timer_tick(void)
|
||||
{
|
||||
if (_external) {
|
||||
LinuxUARTDriver::_timer_tick();
|
||||
UARTDriver::_timer_tick();
|
||||
return;
|
||||
}
|
||||
/* lower the update rate */
|
||||
@ -234,7 +234,7 @@ void LinuxSPIUARTDriver::_timer_tick(void)
|
||||
return;
|
||||
}
|
||||
|
||||
LinuxUARTDriver::_timer_tick();
|
||||
UARTDriver::_timer_tick();
|
||||
|
||||
_last_update_timestamp = hal.scheduler->micros();
|
||||
}
|
||||
|
@ -6,9 +6,9 @@
|
||||
#include "UARTDriver.h"
|
||||
|
||||
|
||||
class Linux::LinuxSPIUARTDriver : public Linux::LinuxUARTDriver {
|
||||
class Linux::SPIUARTDriver : public Linux::UARTDriver {
|
||||
public:
|
||||
LinuxSPIUARTDriver();
|
||||
SPIUARTDriver();
|
||||
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
||||
void _timer_tick(void);
|
||||
|
||||
|
@ -43,10 +43,10 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
||||
|
||||
LinuxScheduler::LinuxScheduler()
|
||||
Scheduler::Scheduler()
|
||||
{}
|
||||
|
||||
void LinuxScheduler::_create_realtime_thread(pthread_t *ctx, int rtprio,
|
||||
void Scheduler::_create_realtime_thread(pthread_t *ctx, int rtprio,
|
||||
const char *name,
|
||||
pthread_startroutine_t start_routine)
|
||||
{
|
||||
@ -78,7 +78,7 @@ void LinuxScheduler::_create_realtime_thread(pthread_t *ctx, int rtprio,
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxScheduler::init(void* machtnichts)
|
||||
void Scheduler::init(void* machtnichts)
|
||||
{
|
||||
mlockall(MCL_CURRENT|MCL_FUTURE);
|
||||
|
||||
@ -96,27 +96,27 @@ void LinuxScheduler::init(void* machtnichts)
|
||||
{ .ctx = &_timer_thread_ctx,
|
||||
.rtprio = APM_LINUX_TIMER_PRIORITY,
|
||||
.name = "sched-timer",
|
||||
.start_routine = &Linux::LinuxScheduler::_timer_thread,
|
||||
.start_routine = &Linux::Scheduler::_timer_thread,
|
||||
},
|
||||
{ .ctx = &_uart_thread_ctx,
|
||||
.rtprio = APM_LINUX_UART_PRIORITY,
|
||||
.name = "sched-uart",
|
||||
.start_routine = &Linux::LinuxScheduler::_uart_thread,
|
||||
.start_routine = &Linux::Scheduler::_uart_thread,
|
||||
},
|
||||
{ .ctx = &_rcin_thread_ctx,
|
||||
.rtprio = APM_LINUX_RCIN_PRIORITY,
|
||||
.name = "sched-rcin",
|
||||
.start_routine = &Linux::LinuxScheduler::_rcin_thread,
|
||||
.start_routine = &Linux::Scheduler::_rcin_thread,
|
||||
},
|
||||
{ .ctx = &_tonealarm_thread_ctx,
|
||||
.rtprio = APM_LINUX_TONEALARM_PRIORITY,
|
||||
.name = "sched-tonealarm",
|
||||
.start_routine = &Linux::LinuxScheduler::_tonealarm_thread,
|
||||
.start_routine = &Linux::Scheduler::_tonealarm_thread,
|
||||
},
|
||||
{ .ctx = &_io_thread_ctx,
|
||||
.rtprio = APM_LINUX_IO_PRIORITY,
|
||||
.name = "sched-io",
|
||||
.start_routine = &Linux::LinuxScheduler::_io_thread,
|
||||
.start_routine = &Linux::Scheduler::_io_thread,
|
||||
},
|
||||
{ }
|
||||
};
|
||||
@ -130,7 +130,7 @@ void LinuxScheduler::init(void* machtnichts)
|
||||
iter->start_routine);
|
||||
}
|
||||
|
||||
void LinuxScheduler::_microsleep(uint32_t usec)
|
||||
void Scheduler::_microsleep(uint32_t usec)
|
||||
{
|
||||
struct timespec ts;
|
||||
ts.tv_sec = 0;
|
||||
@ -138,7 +138,7 @@ void LinuxScheduler::_microsleep(uint32_t usec)
|
||||
while (nanosleep(&ts, &ts) == -1 && errno == EINTR) ;
|
||||
}
|
||||
|
||||
void LinuxScheduler::delay(uint16_t ms)
|
||||
void Scheduler::delay(uint16_t ms)
|
||||
{
|
||||
if (stopped_clock_usec) {
|
||||
return;
|
||||
@ -156,7 +156,7 @@ void LinuxScheduler::delay(uint16_t ms)
|
||||
}
|
||||
}
|
||||
|
||||
uint64_t LinuxScheduler::millis64()
|
||||
uint64_t Scheduler::millis64()
|
||||
{
|
||||
if (stopped_clock_usec) {
|
||||
return stopped_clock_usec/1000;
|
||||
@ -168,7 +168,7 @@ uint64_t LinuxScheduler::millis64()
|
||||
(_sketch_start_time.tv_nsec*1.0e-9)));
|
||||
}
|
||||
|
||||
uint64_t LinuxScheduler::micros64()
|
||||
uint64_t Scheduler::micros64()
|
||||
{
|
||||
if (stopped_clock_usec) {
|
||||
return stopped_clock_usec;
|
||||
@ -180,17 +180,17 @@ uint64_t LinuxScheduler::micros64()
|
||||
(_sketch_start_time.tv_nsec*1.0e-9)));
|
||||
}
|
||||
|
||||
uint32_t LinuxScheduler::millis()
|
||||
uint32_t Scheduler::millis()
|
||||
{
|
||||
return millis64() & 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
uint32_t LinuxScheduler::micros()
|
||||
uint32_t Scheduler::micros()
|
||||
{
|
||||
return micros64() & 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
void LinuxScheduler::delay_microseconds(uint16_t us)
|
||||
void Scheduler::delay_microseconds(uint16_t us)
|
||||
{
|
||||
if (stopped_clock_usec) {
|
||||
return;
|
||||
@ -198,14 +198,14 @@ void LinuxScheduler::delay_microseconds(uint16_t us)
|
||||
_microsleep(us);
|
||||
}
|
||||
|
||||
void LinuxScheduler::register_delay_callback(AP_HAL::Proc proc,
|
||||
void Scheduler::register_delay_callback(AP_HAL::Proc proc,
|
||||
uint16_t min_time_ms)
|
||||
{
|
||||
_delay_cb = proc;
|
||||
_min_delay_cb_ms = min_time_ms;
|
||||
}
|
||||
|
||||
void LinuxScheduler::register_timer_process(AP_HAL::MemberProc proc)
|
||||
void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
||||
{
|
||||
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
||||
if (_timer_proc[i] == proc) {
|
||||
@ -221,7 +221,7 @@ void LinuxScheduler::register_timer_process(AP_HAL::MemberProc proc)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxScheduler::register_io_process(AP_HAL::MemberProc proc)
|
||||
void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
||||
{
|
||||
for (uint8_t i = 0; i < _num_io_procs; i++) {
|
||||
if (_io_proc[i] == proc) {
|
||||
@ -237,24 +237,24 @@ void LinuxScheduler::register_io_process(AP_HAL::MemberProc proc)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxScheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
||||
void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
||||
{
|
||||
_failsafe = failsafe;
|
||||
}
|
||||
|
||||
void LinuxScheduler::suspend_timer_procs()
|
||||
void Scheduler::suspend_timer_procs()
|
||||
{
|
||||
if (!_timer_semaphore.take(0)) {
|
||||
printf("Failed to take timer semaphore\n");
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxScheduler::resume_timer_procs()
|
||||
void Scheduler::resume_timer_procs()
|
||||
{
|
||||
_timer_semaphore.give();
|
||||
}
|
||||
|
||||
void LinuxScheduler::_run_timers(bool called_from_timer_thread)
|
||||
void Scheduler::_run_timers(bool called_from_timer_thread)
|
||||
{
|
||||
if (_in_timer_proc) {
|
||||
return;
|
||||
@ -273,9 +273,9 @@ void LinuxScheduler::_run_timers(bool called_from_timer_thread)
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
//SPI UART use SPI
|
||||
if (!((LinuxRPIOUARTDriver *)hal.uartC)->isExternal() )
|
||||
if (!((RPIOUARTDriver *)hal.uartC)->isExternal() )
|
||||
{
|
||||
((LinuxRPIOUARTDriver *)hal.uartC)->_timer_tick();
|
||||
((RPIOUARTDriver *)hal.uartC)->_timer_tick();
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -289,9 +289,9 @@ void LinuxScheduler::_run_timers(bool called_from_timer_thread)
|
||||
_in_timer_proc = false;
|
||||
}
|
||||
|
||||
void *LinuxScheduler::_timer_thread(void* arg)
|
||||
void *Scheduler::_timer_thread(void* arg)
|
||||
{
|
||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||
Scheduler* sched = (Scheduler *)arg;
|
||||
|
||||
while (sched->system_initializing()) {
|
||||
poll(NULL, 0, 1);
|
||||
@ -316,7 +316,7 @@ void *LinuxScheduler::_timer_thread(void* arg)
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void LinuxScheduler::_run_io(void)
|
||||
void Scheduler::_run_io(void)
|
||||
{
|
||||
if (!_io_semaphore.take(0)) {
|
||||
return;
|
||||
@ -332,23 +332,23 @@ void LinuxScheduler::_run_io(void)
|
||||
_io_semaphore.give();
|
||||
}
|
||||
|
||||
void *LinuxScheduler::_rcin_thread(void *arg)
|
||||
void *Scheduler::_rcin_thread(void *arg)
|
||||
{
|
||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||
Scheduler* sched = (Scheduler *)arg;
|
||||
|
||||
while (sched->system_initializing()) {
|
||||
poll(NULL, 0, 1);
|
||||
}
|
||||
while (true) {
|
||||
sched->_microsleep(APM_LINUX_RCIN_PERIOD);
|
||||
LinuxRCInput::from(hal.rcin)->_timer_tick();
|
||||
RCInput::from(hal.rcin)->_timer_tick();
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void *LinuxScheduler::_uart_thread(void* arg)
|
||||
void *Scheduler::_uart_thread(void* arg)
|
||||
{
|
||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||
Scheduler* sched = (Scheduler *)arg;
|
||||
|
||||
while (sched->system_initializing()) {
|
||||
poll(NULL, 0, 1);
|
||||
@ -357,24 +357,24 @@ void *LinuxScheduler::_uart_thread(void* arg)
|
||||
sched->_microsleep(APM_LINUX_UART_PERIOD);
|
||||
|
||||
// process any pending serial bytes
|
||||
LinuxUARTDriver::from(hal.uartA)->_timer_tick();
|
||||
LinuxUARTDriver::from(hal.uartB)->_timer_tick();
|
||||
UARTDriver::from(hal.uartA)->_timer_tick();
|
||||
UARTDriver::from(hal.uartB)->_timer_tick();
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
//SPI UART not use SPI
|
||||
if (LinuxRPIOUARTDriver::from(hal.uartC)->isExternal()) {
|
||||
LinuxRPIOUARTDriver::from(hal.uartC)->_timer_tick();
|
||||
if (RPIOUARTDriver::from(hal.uartC)->isExternal()) {
|
||||
RPIOUARTDriver::from(hal.uartC)->_timer_tick();
|
||||
}
|
||||
#else
|
||||
LinuxUARTDriver::from(hal.uartC)->_timer_tick();
|
||||
UARTDriver::from(hal.uartC)->_timer_tick();
|
||||
#endif
|
||||
LinuxUARTDriver::from(hal.uartE)->_timer_tick();
|
||||
UARTDriver::from(hal.uartE)->_timer_tick();
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void *LinuxScheduler::_tonealarm_thread(void* arg)
|
||||
void *Scheduler::_tonealarm_thread(void* arg)
|
||||
{
|
||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||
Scheduler* sched = (Scheduler *)arg;
|
||||
|
||||
while (sched->system_initializing()) {
|
||||
poll(NULL, 0, 1);
|
||||
@ -383,14 +383,14 @@ void *LinuxScheduler::_tonealarm_thread(void* arg)
|
||||
sched->_microsleep(APM_LINUX_TONEALARM_PERIOD);
|
||||
|
||||
// process tone command
|
||||
LinuxUtil::from(hal.util)->_toneAlarm_timer_tick();
|
||||
Util::from(hal.util)->_toneAlarm_timer_tick();
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void *LinuxScheduler::_io_thread(void* arg)
|
||||
void *Scheduler::_io_thread(void* arg)
|
||||
{
|
||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||
Scheduler* sched = (Scheduler *)arg;
|
||||
|
||||
while (sched->system_initializing()) {
|
||||
poll(NULL, 0, 1);
|
||||
@ -399,7 +399,7 @@ void *LinuxScheduler::_io_thread(void* arg)
|
||||
sched->_microsleep(APM_LINUX_IO_PERIOD);
|
||||
|
||||
// process any pending storage writes
|
||||
LinuxStorage::from(hal.storage)->_timer_tick();
|
||||
Storage::from(hal.storage)->_timer_tick();
|
||||
|
||||
// run registered IO procepsses
|
||||
sched->_run_io();
|
||||
@ -407,7 +407,7 @@ void *LinuxScheduler::_io_thread(void* arg)
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void LinuxScheduler::panic(const prog_char_t *errormsg)
|
||||
void Scheduler::panic(const prog_char_t *errormsg)
|
||||
{
|
||||
write(1, errormsg, strlen(errormsg));
|
||||
write(1, "\n", 1);
|
||||
@ -416,22 +416,22 @@ void LinuxScheduler::panic(const prog_char_t *errormsg)
|
||||
exit(1);
|
||||
}
|
||||
|
||||
bool LinuxScheduler::in_timerprocess()
|
||||
bool Scheduler::in_timerprocess()
|
||||
{
|
||||
return _in_timer_proc;
|
||||
}
|
||||
|
||||
void LinuxScheduler::begin_atomic()
|
||||
void Scheduler::begin_atomic()
|
||||
{}
|
||||
|
||||
void LinuxScheduler::end_atomic()
|
||||
void Scheduler::end_atomic()
|
||||
{}
|
||||
|
||||
bool LinuxScheduler::system_initializing() {
|
||||
bool Scheduler::system_initializing() {
|
||||
return !_initialized;
|
||||
}
|
||||
|
||||
void LinuxScheduler::system_initialized()
|
||||
void Scheduler::system_initialized()
|
||||
{
|
||||
if (_initialized) {
|
||||
panic("PANIC: scheduler::system_initialized called more than once");
|
||||
@ -439,12 +439,12 @@ void LinuxScheduler::system_initialized()
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
void LinuxScheduler::reboot(bool hold_in_bootloader)
|
||||
void Scheduler::reboot(bool hold_in_bootloader)
|
||||
{
|
||||
exit(1);
|
||||
}
|
||||
|
||||
void LinuxScheduler::stop_clock(uint64_t time_usec)
|
||||
void Scheduler::stop_clock(uint64_t time_usec)
|
||||
{
|
||||
if (time_usec >= stopped_clock_usec) {
|
||||
stopped_clock_usec = time_usec;
|
||||
|
@ -12,12 +12,12 @@
|
||||
#define LINUX_SCHEDULER_MAX_TIMER_PROCS 10
|
||||
#define LINUX_SCHEDULER_MAX_IO_PROCS 10
|
||||
|
||||
class Linux::LinuxScheduler : public AP_HAL::Scheduler {
|
||||
class Linux::Scheduler : public AP_HAL::Scheduler {
|
||||
|
||||
typedef void *(*pthread_startroutine_t)(void *);
|
||||
|
||||
public:
|
||||
LinuxScheduler();
|
||||
Scheduler();
|
||||
void init(void* machtnichts);
|
||||
void delay(uint16_t ms);
|
||||
uint32_t millis();
|
||||
@ -90,8 +90,8 @@ private:
|
||||
|
||||
uint64_t stopped_clock_usec;
|
||||
|
||||
LinuxSemaphore _timer_semaphore;
|
||||
LinuxSemaphore _io_semaphore;
|
||||
Semaphore _timer_semaphore;
|
||||
Semaphore _io_semaphore;
|
||||
};
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -8,12 +8,12 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
bool LinuxSemaphore::give()
|
||||
bool Semaphore::give()
|
||||
{
|
||||
return pthread_mutex_unlock(&_lock) == 0;
|
||||
}
|
||||
|
||||
bool LinuxSemaphore::take(uint32_t timeout_ms)
|
||||
bool Semaphore::take(uint32_t timeout_ms)
|
||||
{
|
||||
if (timeout_ms == 0) {
|
||||
return pthread_mutex_lock(&_lock) == 0;
|
||||
@ -31,7 +31,7 @@ bool LinuxSemaphore::take(uint32_t timeout_ms)
|
||||
return false;
|
||||
}
|
||||
|
||||
bool LinuxSemaphore::take_nonblocking()
|
||||
bool Semaphore::take_nonblocking()
|
||||
{
|
||||
return pthread_mutex_trylock(&_lock) == 0;
|
||||
}
|
||||
|
@ -8,9 +8,9 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include <pthread.h>
|
||||
|
||||
class Linux::LinuxSemaphore : public AP_HAL::Semaphore {
|
||||
class Linux::Semaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
LinuxSemaphore() {
|
||||
Semaphore() {
|
||||
pthread_mutex_init(&_lock, NULL);
|
||||
}
|
||||
bool give();
|
||||
|
@ -29,7 +29,7 @@ using namespace Linux;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
void LinuxStorage::_storage_create(void)
|
||||
void Storage::_storage_create(void)
|
||||
{
|
||||
mkdir(STORAGE_DIR, 0777);
|
||||
unlink(STORAGE_FILE);
|
||||
@ -48,7 +48,7 @@ void LinuxStorage::_storage_create(void)
|
||||
close(fd);
|
||||
}
|
||||
|
||||
void LinuxStorage::_storage_open(void)
|
||||
void Storage::_storage_open(void)
|
||||
{
|
||||
if (_initialised) {
|
||||
return;
|
||||
@ -97,7 +97,7 @@ void LinuxStorage::_storage_open(void)
|
||||
result is that a line is written more than once, but it won't result
|
||||
in a line not being written.
|
||||
*/
|
||||
void LinuxStorage::_mark_dirty(uint16_t loc, uint16_t length)
|
||||
void Storage::_mark_dirty(uint16_t loc, uint16_t length)
|
||||
{
|
||||
uint16_t end = loc + length;
|
||||
for (uint8_t line=loc>>LINUX_STORAGE_LINE_SHIFT;
|
||||
@ -107,7 +107,7 @@ void LinuxStorage::_mark_dirty(uint16_t loc, uint16_t length)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxStorage::read_block(void *dst, uint16_t loc, size_t n)
|
||||
void Storage::read_block(void *dst, uint16_t loc, size_t n)
|
||||
{
|
||||
if (loc >= sizeof(_buffer)-(n-1)) {
|
||||
return;
|
||||
@ -116,7 +116,7 @@ void LinuxStorage::read_block(void *dst, uint16_t loc, size_t n)
|
||||
memcpy(dst, &_buffer[loc], n);
|
||||
}
|
||||
|
||||
void LinuxStorage::write_block(uint16_t loc, const void *src, size_t n)
|
||||
void Storage::write_block(uint16_t loc, const void *src, size_t n)
|
||||
{
|
||||
if (loc >= sizeof(_buffer)-(n-1)) {
|
||||
return;
|
||||
@ -128,7 +128,7 @@ void LinuxStorage::write_block(uint16_t loc, const void *src, size_t n)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxStorage::_timer_tick(void)
|
||||
void Storage::_timer_tick(void)
|
||||
{
|
||||
if (!_initialised || _dirty_mask == 0) {
|
||||
return;
|
||||
|
@ -16,13 +16,13 @@
|
||||
#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::Storage : public AP_HAL::Storage
|
||||
{
|
||||
public:
|
||||
LinuxStorage() : _fd(-1),_dirty_mask(0) { }
|
||||
Storage() : _fd(-1),_dirty_mask(0) { }
|
||||
|
||||
static LinuxStorage *from(AP_HAL::Storage *storage) {
|
||||
return static_cast<LinuxStorage*>(storage);
|
||||
static Storage *from(AP_HAL::Storage *storage) {
|
||||
return static_cast<Storage*>(storage);
|
||||
}
|
||||
|
||||
void init(void* machtnichts) {}
|
||||
|
@ -21,12 +21,12 @@ using namespace Linux;
|
||||
// card for ArduCopter and ArduPlane
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
LinuxStorage_FRAM::LinuxStorage_FRAM():
|
||||
Storage_FRAM::Storage_FRAM():
|
||||
_spi(NULL),
|
||||
_spi_sem(NULL)
|
||||
{}
|
||||
|
||||
void LinuxStorage_FRAM::_storage_create(void)
|
||||
void Storage_FRAM::_storage_create(void)
|
||||
{
|
||||
|
||||
int fd = open();
|
||||
@ -47,7 +47,7 @@ void LinuxStorage_FRAM::_storage_create(void)
|
||||
close(fd);
|
||||
}
|
||||
|
||||
void LinuxStorage_FRAM::_storage_open(void)
|
||||
void Storage_FRAM::_storage_open(void)
|
||||
{
|
||||
if (_initialised) {
|
||||
return;
|
||||
@ -76,7 +76,7 @@ void LinuxStorage_FRAM::_storage_open(void)
|
||||
_initialised = true;
|
||||
}
|
||||
|
||||
void LinuxStorage_FRAM::_timer_tick(void)
|
||||
void Storage_FRAM::_timer_tick(void)
|
||||
{
|
||||
if (!_initialised || _dirty_mask == 0) {
|
||||
return;
|
||||
@ -130,7 +130,7 @@ void LinuxStorage_FRAM::_timer_tick(void)
|
||||
|
||||
//File control function overloads
|
||||
|
||||
int8_t LinuxStorage_FRAM::open()
|
||||
int8_t Storage_FRAM::open()
|
||||
{
|
||||
if(_initialised){
|
||||
return 0;
|
||||
@ -170,13 +170,13 @@ int8_t LinuxStorage_FRAM::open()
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t LinuxStorage_FRAM::write(uint16_t fd,uint8_t *Buff, uint16_t NumBytes){
|
||||
int32_t Storage_FRAM::write(uint16_t fd,uint8_t *Buff, uint16_t NumBytes){
|
||||
if( _register_write(Buff,fptr,NumBytes) == -1){
|
||||
return -1;
|
||||
}
|
||||
return NumBytes;
|
||||
}
|
||||
int32_t LinuxStorage_FRAM::read(uint16_t fd, uint8_t *Buff, uint16_t NumBytes){
|
||||
int32_t Storage_FRAM::read(uint16_t fd, uint8_t *Buff, uint16_t NumBytes){
|
||||
for(uint16_t i=fptr;i<(fptr+NumBytes);i++){
|
||||
Buff[i-fptr]= _register_read(i,OPCODE_READ);
|
||||
|
||||
@ -187,14 +187,14 @@ int32_t LinuxStorage_FRAM::read(uint16_t fd, uint8_t *Buff, uint16_t NumBytes){
|
||||
fptr+=NumBytes;
|
||||
return NumBytes;
|
||||
}
|
||||
uint32_t LinuxStorage_FRAM::lseek(uint16_t fd,uint32_t offset,uint16_t whence){
|
||||
uint32_t Storage_FRAM::lseek(uint16_t fd,uint32_t offset,uint16_t whence){
|
||||
fptr = offset;
|
||||
return offset;
|
||||
}
|
||||
|
||||
//FRAM I/O functions
|
||||
|
||||
int8_t LinuxStorage_FRAM::_register_write( uint8_t* src, uint16_t addr, uint16_t len ){
|
||||
int8_t Storage_FRAM::_register_write( uint8_t* src, uint16_t addr, uint16_t len ){
|
||||
|
||||
uint8_t *tx;
|
||||
uint8_t *rx;
|
||||
@ -219,7 +219,7 @@ int8_t LinuxStorage_FRAM::_register_write( uint8_t* src, uint16_t addr, uint16_t
|
||||
return len;
|
||||
}
|
||||
|
||||
int8_t LinuxStorage_FRAM::_write_enable(bool enable)
|
||||
int8_t Storage_FRAM::_write_enable(bool enable)
|
||||
{
|
||||
uint8_t tx[2];
|
||||
uint8_t rx[2];
|
||||
@ -236,7 +236,7 @@ int8_t LinuxStorage_FRAM::_write_enable(bool enable)
|
||||
|
||||
}
|
||||
|
||||
int8_t LinuxStorage_FRAM::_register_read( uint16_t addr, uint8_t opcode )
|
||||
int8_t Storage_FRAM::_register_read( uint16_t addr, uint8_t opcode )
|
||||
{
|
||||
uint8_t tx[4] = {opcode, (uint8_t)((addr >> 8U)), (uint8_t)(addr & 0xFF), 0};
|
||||
uint8_t rx[4];
|
||||
@ -247,7 +247,7 @@ int8_t LinuxStorage_FRAM::_register_read( uint16_t addr, uint8_t opcode )
|
||||
return rx[3];
|
||||
}
|
||||
|
||||
int8_t LinuxStorage_FRAM::transaction(uint8_t* tx, uint8_t* rx, uint16_t len){
|
||||
int8_t Storage_FRAM::transaction(uint8_t* tx, uint8_t* rx, uint16_t len){
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
if (!_spi_sem->take(100)) {
|
||||
// FRAM: Unable to get semaphore
|
||||
|
@ -12,10 +12,10 @@
|
||||
#define OPCODE_WRITE 0b0010 /* Write Memory */
|
||||
#define OPCODE_RDID 0b10011111 /* Read Device ID */
|
||||
|
||||
class Linux::LinuxStorage_FRAM : public Linux::LinuxStorage
|
||||
class Linux::Storage_FRAM : public Linux::Storage
|
||||
{
|
||||
public:
|
||||
LinuxStorage_FRAM();
|
||||
Storage_FRAM();
|
||||
void _timer_tick(void);
|
||||
|
||||
private:
|
||||
|
@ -33,7 +33,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
LinuxUARTDriver::LinuxUARTDriver(bool default_console) :
|
||||
UARTDriver::UARTDriver(bool default_console) :
|
||||
device_path(NULL),
|
||||
_packetise(false),
|
||||
_flow_control(FLOW_CONTROL_DISABLE)
|
||||
@ -48,7 +48,7 @@ LinuxUARTDriver::LinuxUARTDriver(bool default_console) :
|
||||
/*
|
||||
set the tty device to use for this UART
|
||||
*/
|
||||
void LinuxUARTDriver::set_device_path(const char *path)
|
||||
void UARTDriver::set_device_path(const char *path)
|
||||
{
|
||||
device_path = path;
|
||||
}
|
||||
@ -56,12 +56,12 @@ void LinuxUARTDriver::set_device_path(const char *path)
|
||||
/*
|
||||
open the tty
|
||||
*/
|
||||
void LinuxUARTDriver::begin(uint32_t b)
|
||||
void UARTDriver::begin(uint32_t b)
|
||||
{
|
||||
begin(b, 0, 0);
|
||||
}
|
||||
|
||||
void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
{
|
||||
if (device_path == NULL && _console) {
|
||||
_device = new ConsoleDevice();
|
||||
@ -116,7 +116,7 @@ void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
_allocate_buffers(rxS, txS);
|
||||
}
|
||||
|
||||
void LinuxUARTDriver::_allocate_buffers(uint16_t rxS, uint16_t txS)
|
||||
void UARTDriver::_allocate_buffers(uint16_t rxS, uint16_t txS)
|
||||
{
|
||||
/* we have enough memory to have a larger transmit buffer for
|
||||
* all ports. This means we don't get delays while waiting to
|
||||
@ -161,7 +161,7 @@ void LinuxUARTDriver::_allocate_buffers(uint16_t rxS, uint16_t txS)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxUARTDriver::_deallocate_buffers()
|
||||
void UARTDriver::_deallocate_buffers()
|
||||
{
|
||||
if (_readbuf) {
|
||||
free(_readbuf);
|
||||
@ -186,7 +186,7 @@ void LinuxUARTDriver::_deallocate_buffers()
|
||||
- tcp:*:1243:wait
|
||||
- udp:192.168.2.15:1243
|
||||
*/
|
||||
LinuxUARTDriver::device_type LinuxUARTDriver::_parseDevicePath(const char *arg)
|
||||
UARTDriver::device_type UARTDriver::_parseDevicePath(const char *arg)
|
||||
{
|
||||
struct stat st;
|
||||
|
||||
@ -249,7 +249,7 @@ errout:
|
||||
}
|
||||
|
||||
|
||||
bool LinuxUARTDriver::_serial_start_connection()
|
||||
bool UARTDriver::_serial_start_connection()
|
||||
{
|
||||
_device = new UARTDevice(device_path);
|
||||
_connected = _device->open();
|
||||
@ -262,7 +262,7 @@ bool LinuxUARTDriver::_serial_start_connection()
|
||||
/*
|
||||
start a UDP connection for the serial port
|
||||
*/
|
||||
void LinuxUARTDriver::_udp_start_connection(void)
|
||||
void UARTDriver::_udp_start_connection(void)
|
||||
{
|
||||
bool bcast = (_flag && strcmp(_flag, "bcast") == 0);
|
||||
_device = new UDPDevice(_ip, _base_port, bcast);
|
||||
@ -273,7 +273,7 @@ void LinuxUARTDriver::_udp_start_connection(void)
|
||||
_packetise = true;
|
||||
}
|
||||
|
||||
void LinuxUARTDriver::_tcp_start_connection(void)
|
||||
void UARTDriver::_tcp_start_connection(void)
|
||||
{
|
||||
bool wait = (_flag && strcmp(_flag, "wait") == 0);
|
||||
_device = new TCPServerDevice(_ip, _base_port, wait);
|
||||
@ -284,7 +284,7 @@ void LinuxUARTDriver::_tcp_start_connection(void)
|
||||
/*
|
||||
shutdown a UART
|
||||
*/
|
||||
void LinuxUARTDriver::end()
|
||||
void UARTDriver::end()
|
||||
{
|
||||
_initialised = false;
|
||||
_connected = false;
|
||||
@ -298,7 +298,7 @@ void LinuxUARTDriver::end()
|
||||
}
|
||||
|
||||
|
||||
void LinuxUARTDriver::flush()
|
||||
void UARTDriver::flush()
|
||||
{
|
||||
// we are not doing any buffering, so flush is a no-op
|
||||
}
|
||||
@ -307,7 +307,7 @@ void LinuxUARTDriver::flush()
|
||||
/*
|
||||
return true if the UART is initialised
|
||||
*/
|
||||
bool LinuxUARTDriver::is_initialized()
|
||||
bool UARTDriver::is_initialized()
|
||||
{
|
||||
return _initialised;
|
||||
}
|
||||
@ -316,7 +316,7 @@ bool LinuxUARTDriver::is_initialized()
|
||||
/*
|
||||
enable or disable blocking writes
|
||||
*/
|
||||
void LinuxUARTDriver::set_blocking_writes(bool blocking)
|
||||
void UARTDriver::set_blocking_writes(bool blocking)
|
||||
{
|
||||
_nonblocking_writes = !blocking;
|
||||
}
|
||||
@ -325,7 +325,7 @@ void LinuxUARTDriver::set_blocking_writes(bool blocking)
|
||||
/*
|
||||
do we have any bytes pending transmission?
|
||||
*/
|
||||
bool LinuxUARTDriver::tx_pending()
|
||||
bool UARTDriver::tx_pending()
|
||||
{
|
||||
return !BUF_EMPTY(_writebuf);
|
||||
}
|
||||
@ -333,7 +333,7 @@ bool LinuxUARTDriver::tx_pending()
|
||||
/*
|
||||
return the number of bytes available to be read
|
||||
*/
|
||||
int16_t LinuxUARTDriver::available()
|
||||
int16_t UARTDriver::available()
|
||||
{
|
||||
if (!_initialised) {
|
||||
return 0;
|
||||
@ -345,7 +345,7 @@ int16_t LinuxUARTDriver::available()
|
||||
/*
|
||||
how many bytes are available in the output buffer?
|
||||
*/
|
||||
int16_t LinuxUARTDriver::txspace()
|
||||
int16_t UARTDriver::txspace()
|
||||
{
|
||||
if (!_initialised) {
|
||||
return 0;
|
||||
@ -354,7 +354,7 @@ int16_t LinuxUARTDriver::txspace()
|
||||
return BUF_SPACE(_writebuf);
|
||||
}
|
||||
|
||||
int16_t LinuxUARTDriver::read()
|
||||
int16_t UARTDriver::read()
|
||||
{
|
||||
uint8_t c;
|
||||
if (!_initialised || _readbuf == NULL) {
|
||||
@ -369,7 +369,7 @@ int16_t LinuxUARTDriver::read()
|
||||
}
|
||||
|
||||
/* Linux implementations of Print virtual methods */
|
||||
size_t LinuxUARTDriver::write(uint8_t c)
|
||||
size_t UARTDriver::write(uint8_t c)
|
||||
{
|
||||
if (!_initialised) {
|
||||
return 0;
|
||||
@ -390,7 +390,7 @@ size_t LinuxUARTDriver::write(uint8_t c)
|
||||
/*
|
||||
write size bytes to the write buffer
|
||||
*/
|
||||
size_t LinuxUARTDriver::write(const uint8_t *buffer, size_t size)
|
||||
size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
if (!_initialised) {
|
||||
return 0;
|
||||
@ -442,7 +442,7 @@ size_t LinuxUARTDriver::write(const uint8_t *buffer, size_t size)
|
||||
/*
|
||||
try writing n bytes, handling an unresponsive port
|
||||
*/
|
||||
int LinuxUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
||||
int UARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
@ -470,7 +470,7 @@ int LinuxUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
||||
/*
|
||||
try reading n bytes, handling an unresponsive port
|
||||
*/
|
||||
int LinuxUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||
int UARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||
{
|
||||
int ret;
|
||||
|
||||
@ -488,7 +488,7 @@ int LinuxUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||
try to push out one lump of pending bytes
|
||||
return true if progress is made
|
||||
*/
|
||||
bool LinuxUARTDriver::_write_pending_bytes(void)
|
||||
bool UARTDriver::_write_pending_bytes(void)
|
||||
{
|
||||
uint16_t n;
|
||||
|
||||
@ -550,7 +550,7 @@ bool LinuxUARTDriver::_write_pending_bytes(void)
|
||||
1kHz in the timer thread. Doing it this way reduces the system call
|
||||
overhead in the main task enormously.
|
||||
*/
|
||||
void LinuxUARTDriver::_timer_tick(void)
|
||||
void UARTDriver::_timer_tick(void)
|
||||
{
|
||||
uint16_t n;
|
||||
|
||||
|
@ -6,12 +6,12 @@
|
||||
|
||||
#include "SerialDevice.h"
|
||||
|
||||
class Linux::LinuxUARTDriver : public AP_HAL::UARTDriver {
|
||||
class Linux::UARTDriver : public AP_HAL::UARTDriver {
|
||||
public:
|
||||
LinuxUARTDriver(bool default_console);
|
||||
UARTDriver(bool default_console);
|
||||
|
||||
static LinuxUARTDriver *from(AP_HAL::UARTDriver *uart) {
|
||||
return static_cast<LinuxUARTDriver*>(uart);
|
||||
static UARTDriver *from(AP_HAL::UARTDriver *uart) {
|
||||
return static_cast<UARTDriver*>(uart);
|
||||
}
|
||||
|
||||
/* Linux implementations of UARTDriver virtual methods */
|
||||
|
@ -17,15 +17,15 @@ using namespace Linux;
|
||||
|
||||
|
||||
static int state;
|
||||
ToneAlarm LinuxUtil::_toneAlarm;
|
||||
ToneAlarm Util::_toneAlarm;
|
||||
|
||||
void LinuxUtil::init(int argc, char * const *argv) {
|
||||
void Util::init(int argc, char * const *argv) {
|
||||
saved_argc = argc;
|
||||
saved_argv = argv;
|
||||
|
||||
#ifdef HAL_UTILS_HEAT
|
||||
#if HAL_UTILS_HEAT == HAL_LINUX_HEAT_PWM
|
||||
_heat = new Linux::LinuxHeatPwm(HAL_LINUX_HEAT_PWM_SYSFS_DIR,
|
||||
_heat = new Linux::HeatPwm(HAL_LINUX_HEAT_PWM_SYSFS_DIR,
|
||||
HAL_LINUX_HEAT_KP,
|
||||
HAL_LINUX_HEAT_KI,
|
||||
HAL_LINUX_HEAT_PERIOD_NS,
|
||||
@ -34,11 +34,11 @@ void LinuxUtil::init(int argc, char * const *argv) {
|
||||
#error Unrecognized Heat
|
||||
#endif // #if
|
||||
#else
|
||||
_heat = new Linux::LinuxHeat();
|
||||
_heat = new Linux::Heat();
|
||||
#endif // #ifdef
|
||||
}
|
||||
|
||||
void LinuxUtil::set_imu_temp(float current)
|
||||
void Util::set_imu_temp(float current)
|
||||
{
|
||||
_heat->set_imu_temp(current);
|
||||
}
|
||||
@ -46,23 +46,23 @@ void LinuxUtil::set_imu_temp(float current)
|
||||
/**
|
||||
return commandline arguments, if available
|
||||
*/
|
||||
void LinuxUtil::commandline_arguments(uint8_t &argc, char * const *&argv)
|
||||
void Util::commandline_arguments(uint8_t &argc, char * const *&argv)
|
||||
{
|
||||
argc = saved_argc;
|
||||
argv = saved_argv;
|
||||
}
|
||||
|
||||
bool LinuxUtil::toneAlarm_init()
|
||||
bool Util::toneAlarm_init()
|
||||
{
|
||||
return _toneAlarm.init();
|
||||
}
|
||||
|
||||
void LinuxUtil::toneAlarm_set_tune(uint8_t tone)
|
||||
void Util::toneAlarm_set_tune(uint8_t tone)
|
||||
{
|
||||
_toneAlarm.set_tune(tone);
|
||||
}
|
||||
|
||||
void LinuxUtil::_toneAlarm_timer_tick(){
|
||||
void Util::_toneAlarm_timer_tick(){
|
||||
if(state == 0){
|
||||
state = state + _toneAlarm.init_tune();
|
||||
}else if(state == 1){
|
||||
@ -80,7 +80,7 @@ void LinuxUtil::_toneAlarm_timer_tick(){
|
||||
|
||||
}
|
||||
|
||||
void LinuxUtil::set_system_clock(uint64_t time_utc_usec)
|
||||
void Util::set_system_clock(uint64_t time_utc_usec)
|
||||
{
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
|
||||
timespec ts;
|
||||
@ -90,7 +90,7 @@ void LinuxUtil::set_system_clock(uint64_t time_utc_usec)
|
||||
#endif
|
||||
}
|
||||
|
||||
bool LinuxUtil::is_chardev_node(const char *path)
|
||||
bool Util::is_chardev_node(const char *path)
|
||||
{
|
||||
struct stat st;
|
||||
|
||||
|
@ -6,10 +6,10 @@
|
||||
#include "AP_HAL_Linux_Namespace.h"
|
||||
#include "ToneAlarmDriver.h"
|
||||
|
||||
class Linux::LinuxUtil : public AP_HAL::Util {
|
||||
class Linux::Util : public AP_HAL::Util {
|
||||
public:
|
||||
static LinuxUtil *from(AP_HAL::Util *util) {
|
||||
return static_cast<LinuxUtil*>(util);
|
||||
static Util *from(AP_HAL::Util *util) {
|
||||
return static_cast<Util*>(util);
|
||||
}
|
||||
|
||||
void init(int argc, char * const *argv);
|
||||
@ -40,7 +40,7 @@ public:
|
||||
|
||||
private:
|
||||
static Linux::ToneAlarm _toneAlarm;
|
||||
Linux::LinuxHeat *_heat;
|
||||
Linux::Heat *_heat;
|
||||
int saved_argc;
|
||||
char* const *saved_argv;
|
||||
const char* custom_log_directory = NULL;
|
||||
|
@ -16,13 +16,13 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
LinuxUtilRPI::LinuxUtilRPI()
|
||||
UtilRPI::UtilRPI()
|
||||
{
|
||||
_check_rpi_version();
|
||||
}
|
||||
|
||||
#define MAX_SIZE_LINE 50
|
||||
int LinuxUtilRPI::_check_rpi_version()
|
||||
int UtilRPI::_check_rpi_version()
|
||||
{
|
||||
char buffer[MAX_SIZE_LINE];
|
||||
const char* hardware_description_entry = "Hardware";
|
||||
@ -61,7 +61,7 @@ int LinuxUtilRPI::_check_rpi_version()
|
||||
return _rpi_version;
|
||||
}
|
||||
|
||||
int LinuxUtilRPI::get_rpi_version() const
|
||||
int UtilRPI::get_rpi_version() const
|
||||
{
|
||||
return _rpi_version;
|
||||
}
|
||||
|
@ -2,12 +2,12 @@
|
||||
|
||||
#include "Util.h"
|
||||
|
||||
class Linux::LinuxUtilRPI : public Linux::LinuxUtil {
|
||||
class Linux::UtilRPI : public Linux::Util {
|
||||
public:
|
||||
LinuxUtilRPI();
|
||||
UtilRPI();
|
||||
|
||||
static LinuxUtilRPI *from(AP_HAL::Util *util) {
|
||||
return static_cast<LinuxUtilRPI*>(util);
|
||||
static UtilRPI *from(AP_HAL::Util *util) {
|
||||
return static_cast<UtilRPI*>(util);
|
||||
}
|
||||
|
||||
/* return the Raspberry Pi version */
|
||||
|
Loading…
Reference in New Issue
Block a user