AP_HAL_Empty: remove prefix from classes

Like was done for AP_HAL_Linux in 2ac96b9 ("AP_HAL_Linux: remove prefix
from AP_HAL_Linux classes"), remove the "Empty" prefix from class names
since we are already inside the Empty namespace.
This commit is contained in:
Lucas De Marchi 2015-12-07 16:53:55 -02:00 committed by Andrew Tridgell
parent f69208d47d
commit 2ffb08b9ca
26 changed files with 167 additions and 177 deletions

View File

@ -1,29 +1,19 @@
#pragma once
#ifndef __AP_HAL_EMPTY_NAMESPACE_H__
#define __AP_HAL_EMPTY_NAMESPACE_H__
/* While not strictly required, names inside the Empty namespace are prefixed
* with Empty for clarity. (Some of our users aren't familiar with all of the
* C++ namespace rules.)
*/
namespace Empty { namespace Empty {
class EmptyUARTDriver; class UARTDriver;
class EmptyI2CDriver; class I2CDriver;
class EmptySPIDeviceManager; class SPIDeviceManager;
class EmptySPIDeviceDriver; class SPIDeviceDriver;
class EmptyAnalogSource; class AnalogSource;
class EmptyAnalogIn; class AnalogIn;
class EmptyStorage; class Storage;
class EmptyGPIO; class GPIO;
class EmptyDigitalSource; class DigitalSource;
class EmptyRCInput; class RCInput;
class EmptyRCOutput; class RCOutput;
class EmptySemaphore; class Semaphore;
class EmptyScheduler; class Scheduler;
class EmptyUtil; class Util;
class EmptyPrivateMember; class PrivateMember;
} }
#endif // __AP_HAL_EMPTY_NAMESPACE_H__

View File

@ -2,46 +2,46 @@
using namespace Empty; using namespace Empty;
EmptyAnalogSource::EmptyAnalogSource(float v) : AnalogSource::AnalogSource(float v) :
_v(v) _v(v)
{} {}
float EmptyAnalogSource::read_average() { float AnalogSource::read_average() {
return _v; return _v;
} }
float EmptyAnalogSource::voltage_average() { float AnalogSource::voltage_average() {
return 5.0f * _v / 1024.0f; return 5.0f * _v / 1024.0f;
} }
float EmptyAnalogSource::voltage_latest() { float AnalogSource::voltage_latest() {
return 5.0f * _v / 1024.0f; return 5.0f * _v / 1024.0f;
} }
float EmptyAnalogSource::read_latest() { float AnalogSource::read_latest() {
return _v; return _v;
} }
void EmptyAnalogSource::set_pin(uint8_t p) void AnalogSource::set_pin(uint8_t p)
{} {}
void EmptyAnalogSource::set_stop_pin(uint8_t p) void AnalogSource::set_stop_pin(uint8_t p)
{} {}
void EmptyAnalogSource::set_settle_time(uint16_t settle_time_ms) void AnalogSource::set_settle_time(uint16_t settle_time_ms)
{} {}
EmptyAnalogIn::EmptyAnalogIn() AnalogIn::AnalogIn()
{} {}
void EmptyAnalogIn::init() void AnalogIn::init()
{} {}
AP_HAL::AnalogSource* EmptyAnalogIn::channel(int16_t n) { AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) {
return new EmptyAnalogSource(1.11); return new AnalogSource(1.11);
} }
float EmptyAnalogIn::board_voltage(void) float AnalogIn::board_voltage(void)
{ {
return 0; return 0;
} }

View File

@ -4,9 +4,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyAnalogSource : public AP_HAL::AnalogSource { class Empty::AnalogSource : public AP_HAL::AnalogSource {
public: public:
EmptyAnalogSource(float v); AnalogSource(float v);
float read_average(); float read_average();
float read_latest(); float read_latest();
void set_pin(uint8_t p); void set_pin(uint8_t p);
@ -19,9 +19,9 @@ private:
float _v; float _v;
}; };
class Empty::EmptyAnalogIn : public AP_HAL::AnalogIn { class Empty::AnalogIn : public AP_HAL::AnalogIn {
public: public:
EmptyAnalogIn(); AnalogIn();
void init(); void init();
AP_HAL::AnalogSource* channel(int16_t n); AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void); float board_voltage(void);

View File

@ -3,62 +3,62 @@
using namespace Empty; using namespace Empty;
EmptyGPIO::EmptyGPIO() GPIO::GPIO()
{} {}
void EmptyGPIO::init() void GPIO::init()
{} {}
void EmptyGPIO::pinMode(uint8_t pin, uint8_t output) void GPIO::pinMode(uint8_t pin, uint8_t output)
{} {}
int8_t EmptyGPIO::analogPinToDigitalPin(uint8_t pin) int8_t GPIO::analogPinToDigitalPin(uint8_t pin)
{ {
return -1; return -1;
} }
uint8_t EmptyGPIO::read(uint8_t pin) { uint8_t GPIO::read(uint8_t pin) {
return 0; return 0;
} }
void EmptyGPIO::write(uint8_t pin, uint8_t value) void GPIO::write(uint8_t pin, uint8_t value)
{} {}
void EmptyGPIO::toggle(uint8_t pin) void GPIO::toggle(uint8_t pin)
{} {}
/* Alternative interface: */ /* Alternative interface: */
AP_HAL::DigitalSource* EmptyGPIO::channel(uint16_t n) { AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
return new EmptyDigitalSource(0); return new DigitalSource(0);
} }
/* Interrupt interface: */ /* Interrupt interface: */
bool EmptyGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, bool GPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
uint8_t mode) { uint8_t mode) {
return true; return true;
} }
bool EmptyGPIO::usb_connected(void) bool GPIO::usb_connected(void)
{ {
return false; return false;
} }
EmptyDigitalSource::EmptyDigitalSource(uint8_t v) : DigitalSource::DigitalSource(uint8_t v) :
_v(v) _v(v)
{} {}
void EmptyDigitalSource::mode(uint8_t output) void DigitalSource::mode(uint8_t output)
{} {}
uint8_t EmptyDigitalSource::read() { uint8_t DigitalSource::read() {
return _v; return _v;
} }
void EmptyDigitalSource::write(uint8_t value) { void DigitalSource::write(uint8_t value) {
_v = value; _v = value;
} }
void EmptyDigitalSource::toggle() { void DigitalSource::toggle() {
_v = !_v; _v = !_v;
} }

View File

@ -4,9 +4,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyGPIO : public AP_HAL::GPIO { class Empty::GPIO : public AP_HAL::GPIO {
public: public:
EmptyGPIO(); GPIO();
void init(); void init();
void pinMode(uint8_t pin, uint8_t output); void pinMode(uint8_t pin, uint8_t output);
int8_t analogPinToDigitalPin(uint8_t pin); int8_t analogPinToDigitalPin(uint8_t pin);
@ -25,9 +25,9 @@ public:
bool usb_connected(void); bool usb_connected(void);
}; };
class Empty::EmptyDigitalSource : public AP_HAL::DigitalSource { class Empty::DigitalSource : public AP_HAL::DigitalSource {
public: public:
EmptyDigitalSource(uint8_t v); DigitalSource(uint8_t v);
void mode(uint8_t output); void mode(uint8_t output);
uint8_t read(); uint8_t read();
void write(uint8_t value); void write(uint8_t value);

View File

@ -9,19 +9,19 @@
using namespace Empty; using namespace Empty;
static EmptyUARTDriver uartADriver; static UARTDriver uartADriver;
static EmptyUARTDriver uartBDriver; static UARTDriver uartBDriver;
static EmptyUARTDriver uartCDriver; static UARTDriver uartCDriver;
static EmptySemaphore i2cSemaphore; static Semaphore i2cSemaphore;
static EmptyI2CDriver i2cDriver(&i2cSemaphore); static I2CDriver i2cDriver(&i2cSemaphore);
static EmptySPIDeviceManager spiDeviceManager; static SPIDeviceManager spiDeviceManager;
static EmptyAnalogIn analogIn; static AnalogIn analogIn;
static EmptyStorage storageDriver; static Storage storageDriver;
static EmptyGPIO gpioDriver; static GPIO gpioDriver;
static EmptyRCInput rcinDriver; static RCInput rcinDriver;
static EmptyRCOutput rcoutDriver; static RCOutput rcoutDriver;
static EmptyScheduler schedulerInstance; static Scheduler schedulerInstance;
static EmptyUtil utilInstance; static Util utilInstance;
HAL_Empty::HAL_Empty() : HAL_Empty::HAL_Empty() :
AP_HAL::HAL( AP_HAL::HAL(
@ -42,7 +42,7 @@ HAL_Empty::HAL_Empty() :
&rcoutDriver, &rcoutDriver,
&schedulerInstance, &schedulerInstance,
&utilInstance), &utilInstance),
_member(new EmptyPrivateMember(123)) _member(new PrivateMember(123))
{} {}
void HAL_Empty::run(int argc, char* const argv[], Callbacks* callbacks) const void HAL_Empty::run(int argc, char* const argv[], Callbacks* callbacks) const

View File

@ -10,5 +10,5 @@ public:
HAL_Empty(); HAL_Empty();
void run(int argc, char* const* argv, Callbacks* callbacks) const override; void run(int argc, char* const* argv, Callbacks* callbacks) const override;
private: private:
Empty::EmptyPrivateMember *_member; Empty::PrivateMember *_member;
}; };

View File

@ -4,35 +4,35 @@
using namespace Empty; using namespace Empty;
void EmptyI2CDriver::begin() {} void I2CDriver::begin() {}
void EmptyI2CDriver::end() {} void I2CDriver::end() {}
void EmptyI2CDriver::setTimeout(uint16_t ms) {} void I2CDriver::setTimeout(uint16_t ms) {}
void EmptyI2CDriver::setHighSpeed(bool active) {} void I2CDriver::setHighSpeed(bool active) {}
uint8_t EmptyI2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data) uint8_t I2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
{return 1;} {return 1;}
uint8_t EmptyI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val) uint8_t I2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
{return 1;} {return 1;}
uint8_t EmptyI2CDriver::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 len, uint8_t* data)
{return 1;} {return 1;}
uint8_t EmptyI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data) uint8_t I2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
{ {
memset(data, 0, len); memset(data, 0, len);
return 0; return 0;
} }
uint8_t EmptyI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data) uint8_t I2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data)
{ {
*data = 0; *data = 0;
return 1; return 1;
} }
uint8_t EmptyI2CDriver::readRegisters(uint8_t addr, uint8_t reg, uint8_t I2CDriver::readRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data) uint8_t len, uint8_t* data)
{ {
memset(data, 0, len); memset(data, 0, len);
return 1; return 1;
} }
uint8_t EmptyI2CDriver::lockup_count() {return 0;} uint8_t I2CDriver::lockup_count() {return 0;}

View File

@ -4,9 +4,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyI2CDriver : public AP_HAL::I2CDriver { class Empty::I2CDriver : public AP_HAL::I2CDriver {
public: public:
EmptyI2CDriver(AP_HAL::Semaphore* semaphore) : _semaphore(semaphore) {} I2CDriver(AP_HAL::Semaphore* semaphore) : _semaphore(semaphore) {}
void begin(); void begin();
void end(); void end();
void setTimeout(uint16_t ms); void setTimeout(uint16_t ms);

View File

@ -3,9 +3,9 @@
using namespace Empty; using namespace Empty;
EmptyPrivateMember::EmptyPrivateMember(uint16_t foo) : PrivateMember::PrivateMember(uint16_t foo) :
_foo(foo) _foo(foo)
{} {}
void EmptyPrivateMember::init() {} void PrivateMember::init() {}

View File

@ -7,9 +7,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyPrivateMember { class Empty::PrivateMember {
public: public:
EmptyPrivateMember(uint16_t foo); PrivateMember(uint16_t foo);
void init(); void init();
private: private:
uint16_t _foo; uint16_t _foo;

View File

@ -2,26 +2,26 @@
#include "RCInput.h" #include "RCInput.h"
using namespace Empty; using namespace Empty;
EmptyRCInput::EmptyRCInput() RCInput::RCInput()
{} {}
void EmptyRCInput::init() void RCInput::init()
{} {}
bool EmptyRCInput::new_input() { bool RCInput::new_input() {
return false; return false;
} }
uint8_t EmptyRCInput::num_channels() { uint8_t RCInput::num_channels() {
return 0; return 0;
} }
uint16_t EmptyRCInput::read(uint8_t ch) { uint16_t RCInput::read(uint8_t ch) {
if (ch == 2) return 900; /* throttle should be low, for safety */ if (ch == 2) return 900; /* throttle should be low, for safety */
else return 1500; else return 1500;
} }
uint8_t EmptyRCInput::read(uint16_t* periods, uint8_t len) { uint8_t RCInput::read(uint16_t* periods, uint8_t len) {
for (uint8_t i = 0; i < len; i++){ for (uint8_t i = 0; i < len; i++){
if (i == 2) periods[i] = 900; if (i == 2) periods[i] = 900;
else periods[i] = 1500; else periods[i] = 1500;
@ -29,14 +29,14 @@ uint8_t EmptyRCInput::read(uint16_t* periods, uint8_t len) {
return len; return len;
} }
bool EmptyRCInput::set_overrides(int16_t *overrides, uint8_t len) { bool RCInput::set_overrides(int16_t *overrides, uint8_t len) {
return true; return true;
} }
bool EmptyRCInput::set_override(uint8_t channel, int16_t override) { bool RCInput::set_override(uint8_t channel, int16_t override) {
return true; return true;
} }
void EmptyRCInput::clear_overrides() void RCInput::clear_overrides()
{} {}

View File

@ -4,9 +4,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyRCInput : public AP_HAL::RCInput { class Empty::RCInput : public AP_HAL::RCInput {
public: public:
EmptyRCInput(); RCInput();
void init(); void init();
bool new_input(); bool new_input();
uint8_t num_channels(); uint8_t num_channels();

View File

@ -3,27 +3,27 @@
using namespace Empty; using namespace Empty;
void EmptyRCOutput::init() {} void RCOutput::init() {}
void EmptyRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {} void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {}
uint16_t EmptyRCOutput::get_freq(uint8_t ch) { uint16_t RCOutput::get_freq(uint8_t ch) {
return 50; return 50;
} }
void EmptyRCOutput::enable_ch(uint8_t ch) void RCOutput::enable_ch(uint8_t ch)
{} {}
void EmptyRCOutput::disable_ch(uint8_t ch) void RCOutput::disable_ch(uint8_t ch)
{} {}
void EmptyRCOutput::write(uint8_t ch, uint16_t period_us) void RCOutput::write(uint8_t ch, uint16_t period_us)
{} {}
uint16_t EmptyRCOutput::read(uint8_t ch) { uint16_t RCOutput::read(uint8_t ch) {
return 900; return 900;
} }
void EmptyRCOutput::read(uint16_t* period_us, uint8_t len) void RCOutput::read(uint16_t* period_us, uint8_t len)
{} {}

View File

@ -4,7 +4,7 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyRCOutput : public AP_HAL::RCOutput { class Empty::RCOutput : public AP_HAL::RCOutput {
void init(); void init();
void set_freq(uint32_t chmask, uint16_t freq_hz); void set_freq(uint32_t chmask, uint16_t freq_hz);
uint16_t get_freq(uint8_t ch); uint16_t get_freq(uint8_t ch);

View File

@ -3,45 +3,45 @@
using namespace Empty; using namespace Empty;
EmptySPIDeviceDriver::EmptySPIDeviceDriver() SPIDeviceDriver::SPIDeviceDriver()
{} {}
void EmptySPIDeviceDriver::init() void SPIDeviceDriver::init()
{} {}
AP_HAL::Semaphore* EmptySPIDeviceDriver::get_semaphore() AP_HAL::Semaphore* SPIDeviceDriver::get_semaphore()
{ {
return &_semaphore; return &_semaphore;
} }
bool EmptySPIDeviceDriver::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 true; return true;
} }
void EmptySPIDeviceDriver::cs_assert() void SPIDeviceDriver::cs_assert()
{} {}
void EmptySPIDeviceDriver::cs_release() void SPIDeviceDriver::cs_release()
{} {}
uint8_t EmptySPIDeviceDriver::transfer (uint8_t data) uint8_t SPIDeviceDriver::transfer (uint8_t data)
{ {
return 0; return 0;
} }
void EmptySPIDeviceDriver::transfer (const uint8_t *data, uint16_t len) void SPIDeviceDriver::transfer (const uint8_t *data, uint16_t len)
{ {
} }
EmptySPIDeviceManager::EmptySPIDeviceManager() SPIDeviceManager::SPIDeviceManager()
{} {}
void EmptySPIDeviceManager::init() void SPIDeviceManager::init()
{} {}
AP_HAL::SPIDeviceDriver* EmptySPIDeviceManager::device(enum AP_HAL::SPIDevice, uint8_t index) AP_HAL::SPIDeviceDriver* SPIDeviceManager::device(enum AP_HAL::SPIDevice, uint8_t index)
{ {
return &_device; return &_device;
} }

View File

@ -5,9 +5,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
#include "Semaphores.h" #include "Semaphores.h"
class Empty::EmptySPIDeviceDriver : public AP_HAL::SPIDeviceDriver { class Empty::SPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
public: public:
EmptySPIDeviceDriver(); SPIDeviceDriver();
void init(); void init();
AP_HAL::Semaphore* get_semaphore(); AP_HAL::Semaphore* get_semaphore();
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len); bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
@ -17,16 +17,16 @@ public:
uint8_t transfer (uint8_t data); uint8_t transfer (uint8_t data);
void transfer (const uint8_t *data, uint16_t len); void transfer (const uint8_t *data, uint16_t len);
private: private:
EmptySemaphore _semaphore; Semaphore _semaphore;
}; };
class Empty::EmptySPIDeviceManager : public AP_HAL::SPIDeviceManager { class Empty::SPIDeviceManager : public AP_HAL::SPIDeviceManager {
public: public:
EmptySPIDeviceManager(); SPIDeviceManager();
void init(); void init();
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index); AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index);
private: private:
EmptySPIDeviceDriver _device; SPIDeviceDriver _device;
}; };
#endif // __AP_HAL_EMPTY_SPIDRIVER_H__ #endif // __AP_HAL_EMPTY_SPIDRIVER_H__

View File

@ -7,54 +7,54 @@ using namespace Empty;
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
EmptyScheduler::EmptyScheduler() Scheduler::Scheduler()
{} {}
void EmptyScheduler::init() void Scheduler::init()
{} {}
void EmptyScheduler::delay(uint16_t ms) void Scheduler::delay(uint16_t ms)
{} {}
void EmptyScheduler::delay_microseconds(uint16_t us) void Scheduler::delay_microseconds(uint16_t us)
{} {}
void EmptyScheduler::register_delay_callback(AP_HAL::Proc k, void Scheduler::register_delay_callback(AP_HAL::Proc k,
uint16_t min_time_ms) uint16_t min_time_ms)
{} {}
void EmptyScheduler::register_timer_process(AP_HAL::MemberProc k) void Scheduler::register_timer_process(AP_HAL::MemberProc k)
{} {}
void EmptyScheduler::register_io_process(AP_HAL::MemberProc k) void Scheduler::register_io_process(AP_HAL::MemberProc k)
{} {}
void EmptyScheduler::register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) void Scheduler::register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
{} {}
void EmptyScheduler::suspend_timer_procs() void Scheduler::suspend_timer_procs()
{} {}
void EmptyScheduler::resume_timer_procs() void Scheduler::resume_timer_procs()
{} {}
bool EmptyScheduler::in_timerprocess() { bool Scheduler::in_timerprocess() {
return false; return false;
} }
void EmptyScheduler::begin_atomic() void Scheduler::begin_atomic()
{} {}
void EmptyScheduler::end_atomic() void Scheduler::end_atomic()
{} {}
bool EmptyScheduler::system_initializing() { bool Scheduler::system_initializing() {
return false; return false;
} }
void EmptyScheduler::system_initialized() void Scheduler::system_initialized()
{} {}
void EmptyScheduler::reboot(bool hold_in_bootloader) { void Scheduler::reboot(bool hold_in_bootloader) {
for(;;); for(;;);
} }

View File

@ -4,9 +4,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyScheduler : public AP_HAL::Scheduler { class Empty::Scheduler : public AP_HAL::Scheduler {
public: public:
EmptyScheduler(); Scheduler();
void init(); void init();
void delay(uint16_t ms); void delay(uint16_t ms);
void delay_microseconds(uint16_t us); void delay_microseconds(uint16_t us);

View File

@ -3,7 +3,7 @@
using namespace Empty; using namespace Empty;
bool EmptySemaphore::give() { bool Semaphore::give() {
if (_taken) { if (_taken) {
_taken = false; _taken = false;
return true; return true;
@ -12,11 +12,11 @@ bool EmptySemaphore::give() {
} }
} }
bool EmptySemaphore::take(uint32_t timeout_ms) { bool Semaphore::take(uint32_t timeout_ms) {
return take_nonblocking(); return take_nonblocking();
} }
bool EmptySemaphore::take_nonblocking() { bool Semaphore::take_nonblocking() {
/* No syncronisation primitives to garuntee this is correct */ /* No syncronisation primitives to garuntee this is correct */
if (!_taken) { if (!_taken) {
_taken = true; _taken = true;

View File

@ -4,9 +4,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptySemaphore : public AP_HAL::Semaphore { class Empty::Semaphore : public AP_HAL::Semaphore {
public: public:
EmptySemaphore() : _taken(false) {} Semaphore() : _taken(false) {}
bool give(); bool give();
bool take(uint32_t timeout_ms); bool take(uint32_t timeout_ms);
bool take_nonblocking(); bool take_nonblocking();

View File

@ -4,16 +4,16 @@
using namespace Empty; using namespace Empty;
EmptyStorage::EmptyStorage() Storage::Storage()
{} {}
void EmptyStorage::init() void Storage::init()
{} {}
void EmptyStorage::read_block(void* dst, uint16_t src, size_t n) { void Storage::read_block(void* dst, uint16_t src, size_t n) {
memset(dst, 0, n); memset(dst, 0, n);
} }
void EmptyStorage::write_block(uint16_t loc, const void* src, size_t n) void Storage::write_block(uint16_t loc, const void* src, size_t n)
{} {}

View File

@ -4,9 +4,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyStorage : public AP_HAL::Storage { class Empty::Storage : public AP_HAL::Storage {
public: public:
EmptyStorage(); Storage();
void init(); void init();
void read_block(void *dst, uint16_t src, size_t n); void read_block(void *dst, uint16_t src, size_t n);
void write_block(uint16_t dst, const void* src, size_t n); void write_block(uint16_t dst, const void* src, size_t n);

View File

@ -3,25 +3,25 @@
using namespace Empty; using namespace Empty;
EmptyUARTDriver::EmptyUARTDriver() {} UARTDriver::UARTDriver() {}
void EmptyUARTDriver::begin(uint32_t b) {} void UARTDriver::begin(uint32_t b) {}
void EmptyUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) {} void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) {}
void EmptyUARTDriver::end() {} void UARTDriver::end() {}
void EmptyUARTDriver::flush() {} void UARTDriver::flush() {}
bool EmptyUARTDriver::is_initialized() { return false; } bool UARTDriver::is_initialized() { return false; }
void EmptyUARTDriver::set_blocking_writes(bool blocking) {} void UARTDriver::set_blocking_writes(bool blocking) {}
bool EmptyUARTDriver::tx_pending() { return false; } bool UARTDriver::tx_pending() { return false; }
/* Empty implementations of Stream virtual methods */ /* Empty implementations of Stream virtual methods */
int16_t EmptyUARTDriver::available() { return 0; } int16_t UARTDriver::available() { return 0; }
int16_t EmptyUARTDriver::txspace() { return 1; } int16_t UARTDriver::txspace() { return 1; }
int16_t EmptyUARTDriver::read() { return -1; } int16_t UARTDriver::read() { return -1; }
/* Empty implementations of Print virtual methods */ /* Empty implementations of Print virtual methods */
size_t EmptyUARTDriver::write(uint8_t c) { return 0; } size_t UARTDriver::write(uint8_t c) { return 0; }
size_t EmptyUARTDriver::write(const uint8_t *buffer, size_t size) size_t UARTDriver::write(const uint8_t *buffer, size_t size)
{ {
size_t n = 0; size_t n = 0;
while (size--) { while (size--) {

View File

@ -4,9 +4,9 @@
#include "AP_HAL_Empty.h" #include "AP_HAL_Empty.h"
class Empty::EmptyUARTDriver : public AP_HAL::UARTDriver { class Empty::UARTDriver : public AP_HAL::UARTDriver {
public: public:
EmptyUARTDriver(); UARTDriver();
/* Empty implementations of UARTDriver virtual methods */ /* Empty implementations of UARTDriver virtual methods */
void begin(uint32_t b); void begin(uint32_t b);
void begin(uint32_t b, uint16_t rxS, uint16_t txS); void begin(uint32_t b, uint16_t rxS, uint16_t txS);

View File

@ -5,7 +5,7 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_HAL_Empty_Namespace.h" #include "AP_HAL_Empty_Namespace.h"
class Empty::EmptyUtil : public AP_HAL::Util { class Empty::Util : public AP_HAL::Util {
public: public:
bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; } bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; }
}; };