mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Empty: finished up scaffolding
This commit is contained in:
parent
4c930b77a4
commit
de6f9e52b2
|
@ -25,11 +25,11 @@ EmptyAnalogIn::EmptyAnalogIn()
|
|||
void EmptyAnalogIn::init(void* machtnichts)
|
||||
{}
|
||||
|
||||
AP_HAL::AnalogSource* channel(int16_t n) {
|
||||
AP_HAL::AnalogSource* EmptyAnalogIn::channel(int16_t n) {
|
||||
return new EmptyAnalogSource(1.11);
|
||||
}
|
||||
|
||||
AP_HAL::AnalogSource* channel(int16_t n, float scale) {
|
||||
AP_HAL::AnalogSource* EmptyAnalogIn::channel(int16_t n, float scale) {
|
||||
return new EmptyAnalogSource(scale/2);
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,68 @@
|
|||
#include <stdarg.h>
|
||||
#include "Console.h"
|
||||
|
||||
using namespace Empty;
|
||||
|
||||
EmptyConsoleDriver::EmptyConsoleDriver(AP_HAL::BetterStream* delegate) :
|
||||
_d(delegate)
|
||||
{}
|
||||
|
||||
void EmptyConsoleDriver::init(void* machtnichts)
|
||||
{}
|
||||
|
||||
void EmptyConsoleDriver::backend_open()
|
||||
{}
|
||||
|
||||
void EmptyConsoleDriver::backend_close()
|
||||
{}
|
||||
|
||||
size_t EmptyConsoleDriver::backend_read(uint8_t *data, size_t len) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t EmptyConsoleDriver::backend_write(const uint8_t *data, size_t len) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
void EmptyConsoleDriver::print_P(const prog_char_t *pstr) {
|
||||
_d->print_P(pstr);
|
||||
}
|
||||
|
||||
void EmptyConsoleDriver::println_P(const prog_char_t *pstr) {
|
||||
_d->println_P(pstr);
|
||||
}
|
||||
|
||||
void EmptyConsoleDriver::printf(const char *pstr, ...) {
|
||||
va_list ap;
|
||||
va_start(ap, pstr);
|
||||
_d->printf(pstr, ap);
|
||||
va_end(ap);
|
||||
}
|
||||
|
||||
void EmptyConsoleDriver::_printf_P(const prog_char *pstr, ...) {
|
||||
va_list ap;
|
||||
va_start(ap, pstr);
|
||||
_d->printf_P(pstr, ap);
|
||||
va_end(ap);
|
||||
}
|
||||
|
||||
int16_t EmptyConsoleDriver::available() {
|
||||
return _d->available();
|
||||
}
|
||||
|
||||
int16_t EmptyConsoleDriver::txspace() {
|
||||
return _d->txspace();
|
||||
}
|
||||
|
||||
int16_t EmptyConsoleDriver::read() {
|
||||
return _d->read();
|
||||
}
|
||||
|
||||
int16_t EmptyConsoleDriver::peek() {
|
||||
return _d->peek();
|
||||
}
|
||||
|
||||
size_t EmptyConsoleDriver::write(uint8_t c) {
|
||||
return _d->write(c);
|
||||
}
|
||||
|
|
@ -5,7 +5,27 @@
|
|||
#include <AP_HAL_Empty.h>
|
||||
|
||||
class Empty::EmptyConsoleDriver : public AP_HAL::ConsoleDriver {
|
||||
public:
|
||||
EmptyConsoleDriver(AP_HAL::BetterStream* delegate);
|
||||
void init(void* machtnichts);
|
||||
void backend_open();
|
||||
void backend_close();
|
||||
size_t backend_read(uint8_t *data, size_t len);
|
||||
size_t backend_write(const uint8_t *data, size_t len);
|
||||
|
||||
void print_P(const prog_char_t *pstr);
|
||||
void println_P(const prog_char_t *pstr);
|
||||
void printf(const char *pstr, ...);
|
||||
void _printf_P(const prog_char *pstr, ...);
|
||||
|
||||
int16_t available();
|
||||
int16_t txspace();
|
||||
int16_t read();
|
||||
int16_t peek();
|
||||
|
||||
size_t write(uint8_t c);
|
||||
private:
|
||||
AP_HAL::BetterStream *_d;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_EMPTY_CONSOLE_H__
|
||||
|
|
|
@ -21,7 +21,7 @@ void EmptyGPIO::write(uint8_t pin, uint8_t value)
|
|||
{}
|
||||
|
||||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* channel(uint16_t n) {
|
||||
AP_HAL::DigitalSource* EmptyGPIO::channel(uint16_t n) {
|
||||
return new EmptyDigitalSource(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -13,10 +13,11 @@ static EmptyI2CDriver i2cDriver;
|
|||
static EmptySPIDeviceManager spiDeviceManager;
|
||||
static EmptyAnalogIn analogIn;
|
||||
static EmptyStorage storageDriver;
|
||||
static EmptyConsoleDriver consoleDriver(&uartADriver);
|
||||
static EmptyGPIO gpioDriver;
|
||||
static EmptyRCInput rcinDriver;
|
||||
static EmptyRCOutput rcoutDriver;
|
||||
static EmptyScheduler scheduler;
|
||||
static EmptyScheduler schedulerInstance;
|
||||
|
||||
HAL_Empty::HAL_Empty() :
|
||||
AP_HAL::HAL(
|
||||
|
@ -27,16 +28,21 @@ HAL_Empty::HAL_Empty() :
|
|||
&spiDeviceManager,
|
||||
&analogIn,
|
||||
&storageDriver,
|
||||
&consoleDriver,
|
||||
&gpioDriver,
|
||||
&rcinDriver,
|
||||
&rcoutDriver,
|
||||
&scheduler ),
|
||||
_priv(new EmptyPrivateMember(123))
|
||||
&schedulerInstance),
|
||||
_member(new EmptyPrivateMember(123))
|
||||
{}
|
||||
|
||||
void HAL_Empty::init(int argc, const char * argv[]) const {
|
||||
uartA->init();
|
||||
_priv->init();
|
||||
void HAL_Empty::init(int argc,char* const argv[]) const {
|
||||
/* initialize all drivers and private members here.
|
||||
* up to the programmer to do this in the correct order.
|
||||
* Scheduler should likely come first. */
|
||||
scheduler->init(NULL);
|
||||
uartA->begin(115200);
|
||||
_member->init();
|
||||
}
|
||||
|
||||
const HAL_Empty AP_HAL_Empty;
|
||||
|
|
|
@ -0,0 +1,38 @@
|
|||
|
||||
#include "RCInput.h"
|
||||
|
||||
using namespace Empty;
|
||||
EmptyRCInput::EmptyRCInput()
|
||||
{}
|
||||
|
||||
void EmptyRCInput::init(void* machtnichts)
|
||||
{}
|
||||
|
||||
uint8_t EmptyRCInput::valid() {
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint16_t EmptyRCInput::read(uint8_t ch) {
|
||||
if (ch == 3) return 900; /* throttle should be low, for safety */
|
||||
else return 1500;
|
||||
}
|
||||
|
||||
uint8_t EmptyRCInput::read(uint16_t* periods, uint8_t len) {
|
||||
for (uint8_t i = 0; i < len; i++){
|
||||
if (i == 3) periods[i] = 900;
|
||||
else periods[i] = 1500;
|
||||
}
|
||||
return len;
|
||||
}
|
||||
|
||||
bool EmptyRCInput::set_overrides(int16_t *overrides, uint8_t len) {
|
||||
return true;
|
||||
}
|
||||
|
||||
bool EmptyRCInput::set_override(uint8_t channel, int16_t override) {
|
||||
return true;
|
||||
}
|
||||
|
||||
void EmptyRCInput::clear_overrides()
|
||||
{}
|
||||
|
|
@ -5,7 +5,16 @@
|
|||
#include <AP_HAL_Empty.h>
|
||||
|
||||
class Empty::EmptyRCInput : public AP_HAL::RCInput {
|
||||
public:
|
||||
EmptyRCInput();
|
||||
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();
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_EMPTY_RCINPUT_H__
|
||||
|
|
|
@ -0,0 +1,38 @@
|
|||
|
||||
#include "RCOutput.h"
|
||||
|
||||
using namespace Empty;
|
||||
|
||||
void EmptyRCOutput::init(void* machtnichts) {}
|
||||
|
||||
void EmptyRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {}
|
||||
|
||||
uint16_t EmptyRCOutput::get_freq(uint8_t ch) {
|
||||
return 50;
|
||||
}
|
||||
|
||||
void EmptyRCOutput::enable_ch(uint8_t ch)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::enable_mask(uint32_t chmask)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::disable_ch(uint8_t ch)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::disable_mask(uint32_t chmask)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len)
|
||||
{}
|
||||
|
||||
uint16_t EmptyRCOutput::read(uint8_t ch) {
|
||||
return 900;
|
||||
}
|
||||
|
||||
void EmptyRCOutput::read(uint16_t* period_us, uint8_t len)
|
||||
{}
|
||||
|
|
@ -5,7 +5,17 @@
|
|||
#include <AP_HAL_Empty.h>
|
||||
|
||||
class Empty::EmptyRCOutput : 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);
|
||||
void enable_ch(uint8_t ch);
|
||||
void enable_mask(uint32_t chmask);
|
||||
void disable_ch(uint8_t ch);
|
||||
void disable_mask(uint32_t chmask);
|
||||
void write(uint8_t ch, uint16_t period_us);
|
||||
void write(uint8_t ch, uint16_t* period_us, uint8_t len);
|
||||
uint16_t read(uint8_t ch);
|
||||
void read(uint16_t* period_us, uint8_t len);
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_EMPTY_RCOUTPUT_H__
|
||||
|
|
|
@ -0,0 +1,56 @@
|
|||
|
||||
#include "Scheduler.h"
|
||||
|
||||
using namespace Empty;
|
||||
|
||||
EmptyScheduler::EmptyScheduler()
|
||||
{}
|
||||
|
||||
void EmptyScheduler::init(void* machtnichts)
|
||||
{}
|
||||
|
||||
void EmptyScheduler::delay(uint32_t ms)
|
||||
{}
|
||||
|
||||
uint32_t EmptyScheduler::millis() {
|
||||
return 10000;
|
||||
}
|
||||
|
||||
uint32_t EmptyScheduler::micros() {
|
||||
return 200000;
|
||||
}
|
||||
|
||||
void EmptyScheduler::delay_microseconds(uint16_t us)
|
||||
{}
|
||||
|
||||
void EmptyScheduler::register_delay_callback(AP_HAL::Proc k,
|
||||
uint16_t min_time_ms)
|
||||
{}
|
||||
|
||||
void EmptyScheduler::register_timer_process(AP_HAL::TimedProc k)
|
||||
{}
|
||||
|
||||
bool EmptyScheduler::defer_timer_process(AP_HAL::TimedProc k) {
|
||||
if (k) k(5000);
|
||||
return true;
|
||||
}
|
||||
|
||||
void EmptyScheduler::register_timer_failsafe(AP_HAL::TimedProc,
|
||||
uint32_t period_us)
|
||||
{}
|
||||
|
||||
void EmptyScheduler::suspend_timer_procs()
|
||||
{}
|
||||
|
||||
void EmptyScheduler::resume_timer_procs()
|
||||
{}
|
||||
|
||||
void EmptyScheduler::begin_atomic()
|
||||
{}
|
||||
|
||||
void EmptyScheduler::end_atomic()
|
||||
{}
|
||||
|
||||
void EmptyScheduler::reboot() {
|
||||
for(;;);
|
||||
}
|
|
@ -5,6 +5,26 @@
|
|||
#include <AP_HAL_Empty.h>
|
||||
|
||||
class Empty::EmptyScheduler : public AP_HAL::Scheduler {
|
||||
public:
|
||||
EmptyScheduler();
|
||||
void init(void* machtnichts);
|
||||
void delay(uint32_t ms);
|
||||
uint32_t millis();
|
||||
uint32_t micros();
|
||||
void delay_microseconds(uint16_t us);
|
||||
void register_delay_callback(AP_HAL::Proc,
|
||||
uint16_t min_time_ms);
|
||||
void register_timer_process(AP_HAL::TimedProc);
|
||||
bool defer_timer_process(AP_HAL::TimedProc);
|
||||
void register_timer_failsafe(AP_HAL::TimedProc,
|
||||
uint32_t period_us);
|
||||
void suspend_timer_procs();
|
||||
void resume_timer_procs();
|
||||
|
||||
void begin_atomic();
|
||||
void end_atomic();
|
||||
|
||||
void reboot();
|
||||
|
||||
};
|
||||
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_Empty.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;// = AP_HAL_Empty;
|
||||
const AP_HAL::HAL& hal = AP_HAL_Empty;
|
||||
|
||||
void setup() {}
|
||||
void loop() {}
|
||||
|
|
Loading…
Reference in New Issue