AP_HAL_Linux: remove AP_HAL_Linux_Namespace header
This centralized namespace header encourages centralizing things on umbrella headers that are a pain to maintain. Force each part of AP_HAL_Linux to include what is used. While at it, do some whitespace cleanups and minor changes to adhere to coding style.
This commit is contained in:
parent
5edb03d184
commit
f36e8d9c05
@ -24,11 +24,14 @@
|
||||
#include <AP_HAL_Linux/RCOutput_Bebop.h>
|
||||
#include <AP_HAL_Linux/RCOutput_Disco.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define BATTERY_CAPACITY (1200U) /* mAh */
|
||||
#define BATTERY_VOLTAGE_COMPENSATION_LANDED (0.2f)
|
||||
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
/* polynomial compensation coefficients */
|
||||
static const float bat_comp_polynomial_coeffs[5] = {
|
||||
-1.2471059149657287e-16f,
|
||||
|
@ -1,56 +0,0 @@
|
||||
#pragma once
|
||||
|
||||
namespace Linux {
|
||||
class UARTDriver;
|
||||
class SPIUARTDriver;
|
||||
class RPIOUARTDriver;
|
||||
class I2CDevice;
|
||||
class I2CDeviceManager;
|
||||
class SPIDeviceManager;
|
||||
class SPIDeviceDriver;
|
||||
class Storage;
|
||||
class GPIO_BBB;
|
||||
class GPIO_RPI;
|
||||
class GPIO_Sysfs;
|
||||
class Storage;
|
||||
class DigitalSource;
|
||||
class DigitalSource_Sysfs;
|
||||
class PeriodicThread;
|
||||
class PWM_Sysfs;
|
||||
class PWM_Sysfs_Bebop;
|
||||
class PWM_Sysfs_Base;
|
||||
class RCInput;
|
||||
class RCInput_PRU;
|
||||
class RCInput_AioPRU;
|
||||
class RCInput_RPI;
|
||||
class RCInput_Raspilot;
|
||||
class RCInput_Navio2;
|
||||
class RCInput_ZYNQ;
|
||||
class RCInput_UART;
|
||||
class RCInput_UDP;
|
||||
class RCInput_DSM;
|
||||
class RCInput_SBUS;
|
||||
class RCOutput_PRU;
|
||||
class RCOutput_AioPRU;
|
||||
class RCOutput_PCA9685;
|
||||
class RCOutput_Raspilot;
|
||||
class RCOutput_ZYNQ;
|
||||
class RCOutput_Bebop;
|
||||
class RCOutput_Sysfs;
|
||||
class RCOutput_QFLIGHT;
|
||||
class RCOutput_Disco;
|
||||
class Semaphore;
|
||||
class Scheduler;
|
||||
class Util;
|
||||
class UtilRPI;
|
||||
class ToneAlarm;
|
||||
class ToneAlarm_Raspilot;
|
||||
class Thread;
|
||||
class Heat;
|
||||
class HeatPwm;
|
||||
class CameraSensor;
|
||||
class CameraSensor_Mt9v117;
|
||||
class VideoIn;
|
||||
class OpticalFlow_Onboard;
|
||||
class Flow_PX4;
|
||||
}
|
@ -16,7 +16,9 @@
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
class Linux::CameraSensor {
|
||||
namespace Linux {
|
||||
|
||||
class CameraSensor {
|
||||
public:
|
||||
CameraSensor(const char *device_path) { _device_path = device_path; }
|
||||
|
||||
@ -26,3 +28,5 @@ public:
|
||||
private:
|
||||
const char *_device_path;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -16,7 +16,9 @@
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
class Linux::Flow_PX4 {
|
||||
namespace Linux {
|
||||
|
||||
class Flow_PX4 {
|
||||
public:
|
||||
Flow_PX4(uint32_t width, uint32_t bytesperline,
|
||||
uint32_t max_flow_pixel,
|
||||
@ -35,3 +37,5 @@ private:
|
||||
uint16_t _pixstep;
|
||||
uint8_t _num_blocks;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -2,7 +2,9 @@
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
class Linux::DigitalSource : public AP_HAL::DigitalSource {
|
||||
namespace Linux {
|
||||
|
||||
class DigitalSource : public AP_HAL::DigitalSource {
|
||||
public:
|
||||
DigitalSource(uint8_t v);
|
||||
void mode(uint8_t output);
|
||||
@ -14,6 +16,8 @@ private:
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#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
|
||||
#include "GPIO_BBB.h"
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
|
||||
|
@ -103,7 +103,9 @@
|
||||
#define BBB_P9_41 20
|
||||
#define BBB_P9_42 7
|
||||
|
||||
class Linux::GPIO_BBB : public AP_HAL::GPIO {
|
||||
namespace Linux {
|
||||
|
||||
class GPIO_BBB : public AP_HAL::GPIO {
|
||||
private:
|
||||
struct GPIO {
|
||||
volatile uint32_t *base;
|
||||
@ -131,3 +133,5 @@ public:
|
||||
/* return true if USB cable is connected */
|
||||
bool usb_connected(void);
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -41,7 +41,9 @@
|
||||
#define RPI_GPIO_30 30 // Pin 5
|
||||
#define RPI_GPIO_31 31 // Pin 6
|
||||
|
||||
class Linux::GPIO_RPI : public AP_HAL::GPIO {
|
||||
namespace Linux {
|
||||
|
||||
class GPIO_RPI : public AP_HAL::GPIO {
|
||||
public:
|
||||
GPIO_RPI();
|
||||
void init();
|
||||
@ -65,3 +67,5 @@ public:
|
||||
private:
|
||||
volatile uint32_t *_gpio;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -5,8 +5,10 @@
|
||||
|
||||
#include "GPIO.h"
|
||||
|
||||
class Linux::DigitalSource_Sysfs : public AP_HAL::DigitalSource {
|
||||
friend class Linux::GPIO_Sysfs;
|
||||
namespace Linux {
|
||||
|
||||
class DigitalSource_Sysfs : public AP_HAL::DigitalSource {
|
||||
friend class GPIO_Sysfs;
|
||||
public:
|
||||
~DigitalSource_Sysfs();
|
||||
uint8_t read();
|
||||
@ -23,8 +25,8 @@ private:
|
||||
/**
|
||||
* Generic implementation of AP_HAL::GPIO for Linux based boards.
|
||||
*/
|
||||
class Linux::GPIO_Sysfs : public AP_HAL::GPIO {
|
||||
friend class Linux::DigitalSource_Sysfs;
|
||||
class GPIO_Sysfs : public AP_HAL::GPIO {
|
||||
friend class DigitalSource_Sysfs;
|
||||
public:
|
||||
/* Fill this table with the real pin numbers. */
|
||||
static const unsigned pin_table[];
|
||||
@ -76,3 +78,5 @@ protected:
|
||||
*/
|
||||
static bool _export_pin(uint8_t vpin);
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -2,8 +2,6 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_HAL_Linux_Namespace.h"
|
||||
|
||||
class HAL_Linux : public AP_HAL::HAL {
|
||||
public:
|
||||
HAL_Linux();
|
||||
|
@ -15,8 +15,12 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
class Linux::Heat {
|
||||
namespace Linux {
|
||||
|
||||
class Heat {
|
||||
public:
|
||||
virtual void set_imu_temp(float current) { }
|
||||
virtual void set_imu_target_temp(int8_t *target) { }
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -19,7 +19,9 @@
|
||||
#include "PWM_Sysfs.h"
|
||||
#include "Heat.h"
|
||||
|
||||
class Linux::HeatPwm : public Linux::Heat {
|
||||
namespace Linux {
|
||||
|
||||
class HeatPwm : public Heat {
|
||||
public:
|
||||
HeatPwm(uint8_t pwm_num, float Kp, float Ki,
|
||||
uint32_t period_ns);
|
||||
@ -35,3 +37,5 @@ private:
|
||||
float _sum_error;
|
||||
int8_t *_target = nullptr;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -22,9 +22,12 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "CameraSensor.h"
|
||||
#include "Flow_PX4.h"
|
||||
#include "PWM_Sysfs.h"
|
||||
#include "VideoIn.h"
|
||||
|
||||
class Linux::OpticalFlow_Onboard : public AP_HAL::OpticalFlow {
|
||||
namespace Linux {
|
||||
|
||||
class OpticalFlow_Onboard : public AP_HAL::OpticalFlow {
|
||||
public:
|
||||
void init(AP_HAL::OpticalFlow::Gyro_Cb);
|
||||
bool read(AP_HAL::OpticalFlow::Data_Frame& frame);
|
||||
@ -59,3 +62,5 @@ private:
|
||||
AP_HAL::OpticalFlow::Gyro_Cb _get_gyro;
|
||||
Vector3f _last_gyro_rate;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -5,7 +5,9 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "Util.h"
|
||||
|
||||
class Linux::PWM_Sysfs_Base {
|
||||
namespace Linux {
|
||||
|
||||
class PWM_Sysfs_Base {
|
||||
public:
|
||||
virtual ~PWM_Sysfs_Base();
|
||||
|
||||
@ -51,7 +53,7 @@ private:
|
||||
char *_period_path = NULL;
|
||||
};
|
||||
|
||||
class Linux::PWM_Sysfs : public Linux::PWM_Sysfs_Base {
|
||||
class PWM_Sysfs : public PWM_Sysfs_Base {
|
||||
public:
|
||||
PWM_Sysfs(uint8_t chip, uint8_t channel);
|
||||
|
||||
@ -63,7 +65,7 @@ private:
|
||||
char *_generate_period_path(uint8_t chip, uint8_t channel);
|
||||
};
|
||||
|
||||
class Linux::PWM_Sysfs_Bebop : public Linux::PWM_Sysfs_Base {
|
||||
class PWM_Sysfs_Bebop : public PWM_Sysfs_Base {
|
||||
public:
|
||||
PWM_Sysfs_Bebop(uint8_t channel);
|
||||
|
||||
@ -81,3 +83,5 @@ private:
|
||||
return PWM_Sysfs::NORMAL;
|
||||
}
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -4,7 +4,9 @@
|
||||
|
||||
#define LINUX_RC_INPUT_NUM_CHANNELS 16
|
||||
|
||||
class Linux::RCInput : public AP_HAL::RCInput {
|
||||
namespace Linux {
|
||||
|
||||
class RCInput : public AP_HAL::RCInput {
|
||||
public:
|
||||
RCInput();
|
||||
|
||||
@ -83,5 +85,4 @@ public:
|
||||
} sbus;
|
||||
};
|
||||
|
||||
#include "RCInput_PRU.h"
|
||||
#include "RCInput_ZYNQ.h"
|
||||
}
|
||||
|
@ -18,11 +18,13 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
#define RCIN_PRUSS_RAM_BASE 0x4a303000
|
||||
|
||||
// we use 300 ring buffer entries to guarantee that a full 25 byte
|
||||
// frame of 12 bits per byte
|
||||
|
||||
class Linux::RCInput_AioPRU : public Linux::RCInput
|
||||
{
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_AioPRU : public RCInput {
|
||||
public:
|
||||
void init();
|
||||
void _timer_tick(void);
|
||||
@ -41,3 +43,5 @@ public:
|
||||
};
|
||||
volatile struct ring_buffer *ring_buffer;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -16,12 +16,15 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
||||
|
||||
#include "RCInput.h"
|
||||
#include "RCInput_DSM.h"
|
||||
|
||||
class Linux::RCInput_DSM : public Linux::RCInput
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_DSM : public RCInput
|
||||
{
|
||||
public:
|
||||
void init() override;
|
||||
@ -32,5 +35,7 @@ private:
|
||||
const char *device_path;
|
||||
int32_t fd = -1;
|
||||
};
|
||||
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
||||
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
||||
|
@ -2,8 +2,10 @@
|
||||
|
||||
#include "RCInput.h"
|
||||
|
||||
class Linux::RCInput_Navio2 : public Linux::RCInput
|
||||
{
|
||||
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_Navio2 : public RCInput {
|
||||
public:
|
||||
void init() override;
|
||||
void _timer_tick(void) override;
|
||||
@ -18,3 +20,5 @@ private:
|
||||
int channels[CHANNEL_COUNT];
|
||||
uint16_t periods[ARRAY_SIZE(channels)] = {0};
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -3,6 +3,7 @@
|
||||
#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
|
||||
#include "RCInput_PRU.h"
|
||||
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
|
@ -5,14 +5,15 @@
|
||||
doing the edge detection of the PPM sum input
|
||||
*/
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "RCInput.h"
|
||||
|
||||
#define RCIN_PRUSS_SHAREDRAM_BASE 0x4a312000
|
||||
// we use 300 ring buffer entries to guarantee that a full 25 byte
|
||||
// frame of 12 bits per byte
|
||||
|
||||
class Linux::RCInput_PRU : public Linux::RCInput
|
||||
{
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_PRU : public RCInput {
|
||||
public:
|
||||
void init();
|
||||
void _timer_tick(void);
|
||||
@ -33,3 +34,5 @@ public:
|
||||
// time spent in the low state
|
||||
uint16_t _s0_time;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -22,13 +22,14 @@
|
||||
#include <queue>
|
||||
|
||||
|
||||
namespace Linux {
|
||||
|
||||
enum state_t{
|
||||
RCIN_RPI_INITIAL_STATE = -1,
|
||||
RCIN_RPI_ZERO_STATE = 0,
|
||||
RCIN_RPI_ONE_STATE = 1
|
||||
};
|
||||
|
||||
|
||||
//Memory table structure
|
||||
typedef struct {
|
||||
void **virt_pages;
|
||||
@ -45,7 +46,7 @@ typedef struct {
|
||||
|
||||
class Memory_table {
|
||||
// Allow RCInput_RPI access to private members of Memory_table
|
||||
friend class Linux::RCInput_RPI;
|
||||
friend class RCInput_RPI;
|
||||
|
||||
private:
|
||||
void** _virt_pages;
|
||||
@ -73,7 +74,7 @@ public:
|
||||
};
|
||||
|
||||
|
||||
class Linux::RCInput_RPI : public Linux::RCInput
|
||||
class RCInput_RPI : public RCInput
|
||||
{
|
||||
public:
|
||||
void init();
|
||||
@ -127,5 +128,6 @@ private:
|
||||
void set_sigaction();
|
||||
void set_physical_addresses(int version);
|
||||
void deinit() override;
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -4,7 +4,10 @@
|
||||
#include "RCInput.h"
|
||||
#include <AP_HAL/SPIDevice.h>
|
||||
|
||||
class Linux::RCInput_Raspilot : public Linux::RCInput
|
||||
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_Raspilot : public RCInput
|
||||
{
|
||||
public:
|
||||
void init();
|
||||
@ -16,3 +19,5 @@ private:
|
||||
|
||||
void _poll_data(void);
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -21,7 +21,9 @@
|
||||
#include "RCInput.h"
|
||||
#include "RCInput_SBUS.h"
|
||||
|
||||
class Linux::RCInput_SBUS : public Linux::RCInput
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_SBUS : public RCInput
|
||||
{
|
||||
public:
|
||||
void init() override;
|
||||
@ -32,4 +34,7 @@ private:
|
||||
const char *device_path = "/dev/uart-sbus";
|
||||
int32_t fd = -1;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
||||
|
@ -7,7 +7,9 @@
|
||||
|
||||
#define CHANNELS 8
|
||||
|
||||
class Linux::RCInput_UART : public Linux::RCInput
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_UART : public RCInput
|
||||
{
|
||||
public:
|
||||
RCInput_UART(const char *path);
|
||||
@ -25,3 +27,5 @@ private:
|
||||
uint16_t values[CHANNELS];
|
||||
} _data;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -6,7 +6,9 @@
|
||||
|
||||
#define RCINPUT_UDP_DEF_PORT 777
|
||||
|
||||
class Linux::RCInput_UDP : public Linux::RCInput
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_UDP : public RCInput
|
||||
{
|
||||
public:
|
||||
RCInput_UDP();
|
||||
@ -19,3 +21,5 @@ private:
|
||||
uint64_t _last_buf_ts;
|
||||
uint16_t _last_buf_seq;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -1,3 +1,5 @@
|
||||
#include "RCInput_ZYNQ.h"
|
||||
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
@ -13,7 +15,6 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "GPIO.h"
|
||||
#include "RCInput.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -5,13 +5,14 @@
|
||||
logic doing the edge detection of the PPM sum input
|
||||
*/
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "RCInput.h"
|
||||
|
||||
// FIXME A puppie dies when you hard code an address
|
||||
#define RCIN_ZYNQ_PULSE_INPUT_BASE 0x43c10000
|
||||
|
||||
class Linux::RCInput_ZYNQ : public Linux::RCInput
|
||||
{
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_ZYNQ : public RCInput {
|
||||
public:
|
||||
void init();
|
||||
void _timer_tick(void);
|
||||
@ -26,3 +27,5 @@ public:
|
||||
// time spent in the low state
|
||||
uint32_t _s0_time;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -16,7 +16,9 @@
|
||||
#define RCOUT_PRUSS_IRAM_BASE 0x4a338000
|
||||
#define PWM_CHAN_COUNT 12
|
||||
|
||||
class Linux::RCOutput_AioPRU : public AP_HAL::RCOutput {
|
||||
namespace Linux {
|
||||
|
||||
class RCOutput_AioPRU : public AP_HAL::RCOutput {
|
||||
void init();
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
@ -40,3 +42,5 @@ private:
|
||||
|
||||
volatile struct pwm *pwm;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -3,6 +3,10 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
struct bldc_info;
|
||||
|
||||
namespace Linux {
|
||||
|
||||
enum bebop_bldc_motor {
|
||||
BEBOP_BLDC_MOTOR_1 = 0,
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
@ -49,9 +53,7 @@ public:
|
||||
uint8_t temperature;
|
||||
};
|
||||
|
||||
struct bldc_info;
|
||||
|
||||
class Linux::RCOutput_Bebop : public AP_HAL::RCOutput {
|
||||
class RCOutput_Bebop : public AP_HAL::RCOutput {
|
||||
public:
|
||||
RCOutput_Bebop(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
|
||||
@ -102,3 +104,5 @@ private:
|
||||
void _run_rcout();
|
||||
static void *_control_thread(void *arg);
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -4,7 +4,9 @@
|
||||
#include "RCOutput_Sysfs.h"
|
||||
#include "RCOutput_Bebop.h"
|
||||
|
||||
class Linux::RCOutput_Disco : public AP_HAL::RCOutput {
|
||||
namespace Linux {
|
||||
|
||||
class RCOutput_Disco : public AP_HAL::RCOutput {
|
||||
public:
|
||||
RCOutput_Disco(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
~RCOutput_Disco() {}
|
||||
@ -51,5 +53,6 @@ private:
|
||||
{ sysfs_out, 5 },
|
||||
{ sysfs_out, 0 },
|
||||
};
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -9,7 +9,9 @@
|
||||
#define PCA9685_TERTIARY_ADDRESS 0x42
|
||||
#define PCA9685_QUATENARY_ADDRESS 0x55
|
||||
|
||||
class Linux::RCOutput_PCA9685 : public AP_HAL::RCOutput {
|
||||
namespace Linux {
|
||||
|
||||
class RCOutput_PCA9685 : public AP_HAL::RCOutput {
|
||||
public:
|
||||
RCOutput_PCA9685(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool external_clock,
|
||||
@ -45,3 +47,5 @@ private:
|
||||
int16_t _oe_pin_number;
|
||||
uint16_t _pending_write_mask;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -13,7 +13,9 @@
|
||||
#define PWM_CMD_CLR 5 /* clr a pwm output explicitly */
|
||||
#define PWM_CMD_TEST 6 /* various crap */
|
||||
|
||||
class Linux::RCOutput_PRU : public AP_HAL::RCOutput {
|
||||
namespace Linux {
|
||||
|
||||
class RCOutput_PRU : public AP_HAL::RCOutput {
|
||||
void init();
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
@ -37,3 +39,5 @@ private:
|
||||
volatile struct pwm_cmd *sharedMem_cmd;
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -3,7 +3,10 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include <AP_HAL/SPIDevice.h>
|
||||
|
||||
class Linux::RCOutput_Raspilot : public AP_HAL::RCOutput {
|
||||
namespace Linux {
|
||||
|
||||
class RCOutput_Raspilot : public AP_HAL::RCOutput {
|
||||
public:
|
||||
void init();
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
@ -23,3 +26,5 @@ private:
|
||||
uint16_t _frequency;
|
||||
uint16_t _period_us[8];
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -3,7 +3,9 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "PWM_Sysfs.h"
|
||||
|
||||
class Linux::RCOutput_Sysfs : public AP_HAL::RCOutput {
|
||||
namespace Linux {
|
||||
|
||||
class RCOutput_Sysfs : public AP_HAL::RCOutput {
|
||||
public:
|
||||
RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t channel_count);
|
||||
~RCOutput_Sysfs();
|
||||
@ -28,3 +30,5 @@ private:
|
||||
const uint8_t _channel_count;
|
||||
PWM_Sysfs_Base **_pwm_channels;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -11,8 +11,13 @@
|
||||
#define PWM_CMD_CLR 5 /* clr a pwm output explicitly */
|
||||
#define PWM_CMD_TEST 6 /* various crap */
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
class Linux::RCOutput_ZYNQ : public AP_HAL::RCOutput {
|
||||
namespace Linux {
|
||||
|
||||
|
||||
class RCOutput_ZYNQ : public AP_HAL::RCOutput {
|
||||
public:
|
||||
void init();
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
@ -36,3 +41,5 @@ private:
|
||||
};
|
||||
volatile struct pwm_cmd *sharedMem_cmd;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -5,7 +5,9 @@
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
||||
|
||||
class Linux::RCOutput_QFLIGHT : public AP_HAL::RCOutput {
|
||||
namespace Linux {
|
||||
|
||||
class RCOutput_QFLIGHT : public AP_HAL::RCOutput {
|
||||
public:
|
||||
void init();
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
@ -44,4 +46,6 @@ private:
|
||||
uint8_t nrcin_bytes;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
||||
|
@ -5,8 +5,9 @@
|
||||
#include "UARTDriver.h"
|
||||
#include <AP_HAL/SPIDevice.h>
|
||||
|
||||
namespace Linux {
|
||||
|
||||
class Linux::RPIOUARTDriver : public Linux::UARTDriver {
|
||||
class RPIOUARTDriver : public UARTDriver {
|
||||
public:
|
||||
RPIOUARTDriver();
|
||||
|
||||
@ -37,3 +38,5 @@ private:
|
||||
bool _need_set_baud;
|
||||
uint32_t _baudrate;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -4,8 +4,9 @@
|
||||
|
||||
#include "UARTDriver.h"
|
||||
|
||||
namespace Linux {
|
||||
|
||||
class Linux::SPIUARTDriver : public Linux::UARTDriver {
|
||||
class SPIUARTDriver : public UARTDriver {
|
||||
public:
|
||||
SPIUARTDriver();
|
||||
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
||||
@ -23,3 +24,5 @@ protected:
|
||||
|
||||
bool _external;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -10,7 +10,9 @@
|
||||
#define LINUX_SCHEDULER_MAX_TIMESLICED_PROCS 10
|
||||
#define LINUX_SCHEDULER_MAX_IO_PROCS 10
|
||||
|
||||
class Linux::Scheduler : public AP_HAL::Scheduler {
|
||||
namespace Linux {
|
||||
|
||||
class Scheduler : public AP_HAL::Scheduler {
|
||||
public:
|
||||
Scheduler();
|
||||
|
||||
@ -109,3 +111,5 @@ private:
|
||||
Semaphore _timer_semaphore;
|
||||
Semaphore _io_semaphore;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -6,7 +6,9 @@
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
class Linux::Semaphore : public AP_HAL::Semaphore {
|
||||
namespace Linux {
|
||||
|
||||
class Semaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
Semaphore() {
|
||||
pthread_mutex_init(&_lock, NULL);
|
||||
@ -17,3 +19,5 @@ public:
|
||||
private:
|
||||
pthread_mutex_t _lock;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -1,7 +1,6 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_Linux_Namespace.h"
|
||||
|
||||
#define LINUX_STORAGE_SIZE HAL_STORAGE_SIZE
|
||||
#define LINUX_STORAGE_MAX_WRITE 512
|
||||
@ -9,7 +8,9 @@
|
||||
#define LINUX_STORAGE_LINE_SIZE (1<<LINUX_STORAGE_LINE_SHIFT)
|
||||
#define LINUX_STORAGE_NUM_LINES (LINUX_STORAGE_SIZE/LINUX_STORAGE_LINE_SIZE)
|
||||
|
||||
class Linux::Storage : public AP_HAL::Storage
|
||||
namespace Linux {
|
||||
|
||||
class Storage : public AP_HAL::Storage
|
||||
{
|
||||
public:
|
||||
Storage() : _fd(-1),_dirty_mask(0) { }
|
||||
@ -39,3 +40,5 @@ protected:
|
||||
uint8_t _buffer[LINUX_STORAGE_SIZE];
|
||||
volatile uint32_t _dirty_mask;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -23,8 +23,6 @@
|
||||
|
||||
#include <AP_HAL/utility/functor.h>
|
||||
|
||||
#include "AP_HAL_Linux_Namespace.h"
|
||||
|
||||
namespace Linux {
|
||||
|
||||
/*
|
||||
|
@ -1,7 +1,6 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_Linux_Namespace.h"
|
||||
|
||||
#define OCTAVE_OFFSET 0
|
||||
|
||||
@ -109,7 +108,9 @@
|
||||
|
||||
#define TONE_NUMBER_OF_TUNES 11
|
||||
|
||||
class Linux::ToneAlarm{
|
||||
namespace Linux {
|
||||
|
||||
class ToneAlarm {
|
||||
public:
|
||||
ToneAlarm();
|
||||
void set_tune(uint8_t tone);
|
||||
@ -141,3 +142,5 @@ private:
|
||||
int32_t duty_fd;
|
||||
int32_t run_fd;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -4,7 +4,9 @@
|
||||
|
||||
#include "ToneAlarm.h"
|
||||
|
||||
class Linux::ToneAlarm_Raspilot : public Linux::ToneAlarm {
|
||||
namespace Linux {
|
||||
|
||||
class ToneAlarm_Raspilot : public ToneAlarm {
|
||||
public:
|
||||
ToneAlarm_Raspilot();
|
||||
bool init() override;
|
||||
@ -18,3 +20,5 @@ private:
|
||||
volatile uint32_t *_pwm;
|
||||
volatile uint32_t *_clk;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -5,7 +5,9 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "SerialDevice.h"
|
||||
|
||||
class Linux::UARTDriver : public AP_HAL::UARTDriver {
|
||||
namespace Linux {
|
||||
|
||||
class UARTDriver : public AP_HAL::UARTDriver {
|
||||
public:
|
||||
UARTDriver(bool default_console);
|
||||
|
||||
@ -85,3 +87,5 @@ protected:
|
||||
virtual int _read_fd(uint8_t *buf, uint16_t n);
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -3,11 +3,13 @@
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_HAL_Linux_Namespace.h"
|
||||
#include "Heat.h"
|
||||
#include "Perf.h"
|
||||
#include "ToneAlarm.h"
|
||||
#include "Semaphores.h"
|
||||
|
||||
namespace Linux {
|
||||
|
||||
enum hw_type {
|
||||
UTIL_HARDWARE_RPI1 = 0,
|
||||
UTIL_HARDWARE_RPI2,
|
||||
@ -17,7 +19,7 @@ enum hw_type {
|
||||
UTIL_NUM_HARDWARES,
|
||||
};
|
||||
|
||||
class Linux::Util : public AP_HAL::Util {
|
||||
class Util : public AP_HAL::Util {
|
||||
public:
|
||||
static Util *from(AP_HAL::Util *util) {
|
||||
return static_cast<Util*>(util);
|
||||
@ -87,20 +89,22 @@ public:
|
||||
}
|
||||
|
||||
// create a new semaphore
|
||||
AP_HAL::Semaphore *new_semaphore(void) override { return new Linux::Semaphore; }
|
||||
AP_HAL::Semaphore *new_semaphore(void) override { return new Semaphore; }
|
||||
|
||||
int get_hw_arm32();
|
||||
|
||||
private:
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
static Linux::ToneAlarm_Raspilot _toneAlarm;
|
||||
static ToneAlarm_Raspilot _toneAlarm;
|
||||
#else
|
||||
static Linux::ToneAlarm _toneAlarm;
|
||||
static ToneAlarm _toneAlarm;
|
||||
#endif
|
||||
Linux::Heat *_heat;
|
||||
Heat *_heat;
|
||||
int saved_argc;
|
||||
char* const *saved_argv;
|
||||
const char* custom_log_directory = NULL;
|
||||
const char* custom_terrain_directory = NULL;
|
||||
static const char *_hw_names[UTIL_NUM_HARDWARES];
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -2,7 +2,9 @@
|
||||
|
||||
#include "Util.h"
|
||||
|
||||
class Linux::UtilRPI : public Linux::Util {
|
||||
namespace Linux {
|
||||
|
||||
class UtilRPI : public Util {
|
||||
public:
|
||||
UtilRPI();
|
||||
|
||||
@ -20,3 +22,5 @@ protected:
|
||||
private:
|
||||
int _rpi_version = 0;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -18,12 +18,14 @@
|
||||
#include <linux/videodev2.h>
|
||||
#include <vector>
|
||||
|
||||
namespace Linux {
|
||||
|
||||
struct buffer {
|
||||
unsigned int size;
|
||||
void *mem;
|
||||
};
|
||||
|
||||
class Linux::VideoIn {
|
||||
class VideoIn {
|
||||
public:
|
||||
/* This structure implements the fields of the v4l2_pix_format struct
|
||||
* that are considered useful for an optical flow application along
|
||||
@ -80,3 +82,5 @@ private:
|
||||
uint32_t _sizeimage;
|
||||
uint32_t _memtype = V4L2_MEMORY_MMAP;
|
||||
};
|
||||
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user