HAL_PX4: initial RCInput driver (overrides only)

This commit is contained in:
Andrew Tridgell 2013-01-03 21:30:35 +11:00
parent 85007cb766
commit 38bccee230
4 changed files with 102 additions and 1 deletions

View File

@ -7,6 +7,7 @@ namespace PX4 {
class PX4Scheduler;
class PX4UARTDriver;
class PX4EEPROMStorage;
class PX4RCInput;
}
#endif //__AP_HAL_PX4_NAMESPACE_H__

View File

@ -11,6 +11,7 @@
#include "Scheduler.h"
#include "UARTDriver.h"
#include "Storage.h"
#include "RCInput.h"
#include <AP_HAL_Empty.h>
#include <AP_HAL_Empty_Private.h>
@ -23,13 +24,13 @@ static Empty::EmptyI2CDriver i2cDriver;
static Empty::EmptySPIDeviceManager spiDeviceManager;
static Empty::EmptyAnalogIn analogIn;
static Empty::EmptyGPIO gpioDriver;
static Empty::EmptyRCInput rcinDriver;
static Empty::EmptyRCOutput rcoutDriver;
static Empty::EmptyUtil utilInstance;
static PX4ConsoleDriver consoleDriver;
static PX4Scheduler schedulerInstance;
static PX4EEPROMStorage storageDriver;
static PX4RCInput rcinDriver;
// only one real UART driver for now
static PX4UARTDriver uartADriver("/dev/ttyS0");

View File

@ -0,0 +1,71 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
#include "RCInput.h"
using namespace PX4;
extern const AP_HAL::HAL& hal;
PX4RCInput::PX4RCInput()
{}
void PX4RCInput::init(void* machtnichts)
{
for (uint8_t i=0; i<PX4_NUM_RCINPUT_CHANNELS; i++) {
_override[i] = 1500;
}
// lower throttle
_override[2] = 1000;
}
uint8_t PX4RCInput::valid() {
return hal.scheduler->millis() - _last_read > 20;
}
uint16_t PX4RCInput::read(uint8_t ch) {
_last_read = hal.scheduler->millis();
return _override[ch];
}
uint8_t PX4RCInput::read(uint16_t* periods, uint8_t len) {
if (len > PX4_NUM_RCINPUT_CHANNELS) {
len = PX4_NUM_RCINPUT_CHANNELS;
}
for (uint8_t i = 0; i < len; i++){
periods[i] = read(i);
}
return len;
}
bool PX4RCInput::set_overrides(int16_t *overrides, uint8_t len) {
bool res = false;
for (uint8_t i = 0; i < len; i++) {
res |= set_override(i, overrides[i]);
}
return res;
}
bool PX4RCInput::set_override(uint8_t channel, int16_t override) {
if (override < 0) {
return false; /* -1: no change. */
}
if (channel < PX4_NUM_RCINPUT_CHANNELS) {
_override[channel] = override;
if (override != 0) {
return true;
}
}
return false;
}
void PX4RCInput::clear_overrides()
{
#if 0
for (uint8_t i = 0; i < PX4_NUM_RCINPUT_CHANNELS; i++) {
_override[i] = 0;
}
#endif
}
#endif

View File

@ -0,0 +1,28 @@
#ifndef __AP_HAL_PX4_RCINPUT_H__
#define __AP_HAL_PX4_RCINPUT_H__
#include <AP_HAL_PX4.h>
#define PX4_NUM_RCINPUT_CHANNELS 8
class PX4::PX4RCInput : public AP_HAL::RCInput {
public:
PX4RCInput();
void init(void* machtnichts);
uint8_t valid();
uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len);
bool set_overrides(int16_t *overrides, uint8_t len);
bool set_override(uint8_t channel, int16_t override);
void clear_overrides();
private:
/* override state */
uint16_t _override[PX4_NUM_RCINPUT_CHANNELS];
bool _pwm_valid;
uint32_t _last_read;
};
#endif // __AP_HAL_PX4_RCINPUT_H__