13 changed files with 261 additions and 23 deletions
@ -0,0 +1,35 @@
@@ -0,0 +1,35 @@
|
||||
|
||||
#include "AnalogIn.h" |
||||
|
||||
using namespace Empty; |
||||
|
||||
EmptyAnalogSource::EmptyAnalogSource(float v) : |
||||
_v(v) |
||||
{} |
||||
|
||||
float EmptyAnalogSource::read_average() { |
||||
return _v; |
||||
} |
||||
|
||||
float EmptyAnalogSource::read_latest() { |
||||
return _v; |
||||
} |
||||
|
||||
void EmptyAnalogSource::set_pin(uint8_t p) |
||||
{} |
||||
|
||||
|
||||
EmptyAnalogIn::EmptyAnalogIn() |
||||
{} |
||||
|
||||
void EmptyAnalogIn::init(void* machtnichts) |
||||
{} |
||||
|
||||
AP_HAL::AnalogSource* channel(int16_t n) { |
||||
return new EmptyAnalogSource(1.11); |
||||
} |
||||
|
||||
AP_HAL::AnalogSource* channel(int16_t n, float scale) { |
||||
return new EmptyAnalogSource(scale/2); |
||||
} |
||||
|
@ -0,0 +1,49 @@
@@ -0,0 +1,49 @@
|
||||
|
||||
#include "GPIO.h" |
||||
|
||||
using namespace Empty; |
||||
|
||||
EmptyGPIO::EmptyGPIO() |
||||
{} |
||||
|
||||
void EmptyGPIO::init() |
||||
{} |
||||
|
||||
void EmptyGPIO::pinMode(uint8_t pin, uint8_t output) |
||||
{} |
||||
|
||||
|
||||
uint8_t EmptyGPIO::read(uint8_t pin) { |
||||
return 0; |
||||
} |
||||
|
||||
void EmptyGPIO::write(uint8_t pin, uint8_t value) |
||||
{} |
||||
|
||||
/* Alternative interface: */ |
||||
AP_HAL::DigitalSource* channel(uint16_t n) { |
||||
return new EmptyDigitalSource(0); |
||||
} |
||||
|
||||
/* Interrupt interface: */ |
||||
bool EmptyGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, |
||||
uint8_t mode) { |
||||
return true; |
||||
} |
||||
|
||||
|
||||
EmptyDigitalSource::EmptyDigitalSource(uint8_t v) : |
||||
_v(v) |
||||
{} |
||||
|
||||
void EmptyDigitalSource::mode(uint8_t output) |
||||
{} |
||||
|
||||
uint8_t EmptyDigitalSource::read() { |
||||
return _v; |
||||
} |
||||
|
||||
void EmptyDigitalSource::write(uint8_t value) { |
||||
_v = value; |
||||
} |
||||
|
@ -0,0 +1,40 @@
@@ -0,0 +1,40 @@
|
||||
|
||||
#include "Semaphore.h" |
||||
|
||||
using namespace Empty; |
||||
|
||||
EmptySemaphore::EmptySemaphore() : |
||||
_owner(NULL), |
||||
_k(NULL) |
||||
{} |
||||
|
||||
|
||||
bool EmptySemaphore::get(void* owner) { |
||||
if (_owner == NULL) { |
||||
_owner = owner; |
||||
return true; |
||||
} else { |
||||
return false; |
||||
} |
||||
} |
||||
|
||||
bool EmptySemaphore::release(void* owner) { |
||||
if (_owner == NULL || _owner != owner) { |
||||
return false; |
||||
} else { |
||||
_owner = NULL; |
||||
if (_k){ |
||||
_k(); |
||||
_k = NULL; |
||||
} |
||||
return true; |
||||
} |
||||
} |
||||
|
||||
bool EmptySemaphore::call_on_release(void* caller, AP_HAL::Proc k) { |
||||
/* idk what semantics randy was looking for here, honestly.
|
||||
* seems like a bad idea. */ |
||||
_k = k; |
||||
return true; |
||||
} |
||||
|
@ -0,0 +1,40 @@
@@ -0,0 +1,40 @@
|
||||
|
||||
#include <string.h> |
||||
#include "Storage.h" |
||||
|
||||
using namespace Empty; |
||||
|
||||
EmptyStorage::EmptyStorage() |
||||
{} |
||||
|
||||
void EmptyStorage::init(void*) |
||||
{} |
||||
|
||||
uint8_t EmptyStorage::read_byte(uint16_t loc){ |
||||
return 0; |
||||
} |
||||
|
||||
uint16_t EmptyStorage::read_word(uint16_t loc){ |
||||
return 0; |
||||
} |
||||
|
||||
uint32_t EmptyStorage::read_dword(uint16_t loc){ |
||||
return 0; |
||||
} |
||||
|
||||
void EmptyStorage::read_block(void* dst, uint16_t src, size_t n) { |
||||
memset(dst, 0, n); |
||||
} |
||||
|
||||
void EmptyStorage::write_byte(uint16_t loc, uint8_t value) |
||||
{} |
||||
|
||||
void EmptyStorage::write_word(uint16_t loc, uint16_t value) |
||||
{} |
||||
|
||||
void EmptyStorage::write_dword(uint16_t loc, uint32_t value) |
||||
{} |
||||
|
||||
void EmptyStorage::write_block(uint16_t loc, void* src, size_t n) |
||||
{} |
||||
|
Loading…
Reference in new issue