AP_HAL_Empty: more scaffolding complete

This commit is contained in:
Pat Hickey 2012-12-17 11:07:26 -08:00 committed by Andrew Tridgell
parent 7d27e420ae
commit b7cd4312f3
13 changed files with 260 additions and 22 deletions

View File

@ -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);
}

View File

@ -4,8 +4,21 @@
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty.h>
class Empty::EmptyAnalogIn : public AP_HAL::AnalogIn { class Empty::EmptyAnalogSource : public AP_HAL::AnalogSource {
public:
EmptyAnalogSource(float v);
float read_average();
float read_latest();
void set_pin(uint8_t p);
private:
float _v;
}; };
class Empty::EmptyAnalogIn : public AP_HAL::AnalogIn {
public:
EmptyAnalogIn();
void init(void* implspecific);
AP_HAL::AnalogSource* channel(int16_t n);
AP_HAL::AnalogSource* channel(int16_t n, float scale);
};
#endif // __AP_HAL_EMPTY_ANALOGIN_H__ #endif // __AP_HAL_EMPTY_ANALOGIN_H__

View File

@ -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;
}

View File

@ -5,7 +5,30 @@
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty.h>
class Empty::EmptyGPIO : public AP_HAL::GPIO { class Empty::EmptyGPIO : public AP_HAL::GPIO {
public:
EmptyGPIO();
void init();
void pinMode(uint8_t pin, uint8_t output);
uint8_t read(uint8_t pin);
void write(uint8_t pin, uint8_t value);
/* Alternative interface: */
AP_HAL::DigitalSource* channel(uint16_t n);
/* Interrupt interface: */
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
uint8_t mode);
}; };
class Empty::EmptyDigitalSource : public AP_HAL::DigitalSource {
public:
EmptyDigitalSource(uint8_t v);
void mode(uint8_t output);
uint8_t read();
void write(uint8_t value);
private:
uint8_t _v;
};
#endif // __AP_HAL_EMPTY_GPIO_H__ #endif // __AP_HAL_EMPTY_GPIO_H__

View File

@ -1,8 +1,6 @@
#include <AP_HAL.h> #include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
#include "HAL_Empty_Class.h" #include "HAL_Empty_Class.h"
#include "AP_HAL_Empty_Private.h" #include "AP_HAL_Empty_Private.h"
@ -43,5 +41,3 @@ void HAL_Empty::init(int argc, const char * argv[]) const {
const HAL_Empty AP_HAL_Empty; const HAL_Empty AP_HAL_Empty;
#endif // CONFIG_HAL_BOARD == HAL_BOARD_EMPTY

View File

@ -4,21 +4,18 @@
#include <AP_HAL.h> #include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
#include "AP_HAL_Empty_Namespace.h" #include "AP_HAL_Empty_Namespace.h"
#include "PrivateMember.h" #include "PrivateMember.h"
class HAL_Empty : public AP_HAL::HAL { class HAL_Empty : public AP_HAL::HAL {
public: public:
HAL_Empty(); HAL_Empty();
void init(int argc, const char * argv[]) const; void init(int argc, char * const * argv) const;
private: private:
Empty::EmptyPrivateMember *_member; Empty::EmptyPrivateMember *_member;
}; };
//extern const HAL_Empty AP_HAL_Empty; extern const HAL_Empty AP_HAL_Empty;
#endif // CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
#endif // __AP_HAL_EMPTY_CLASS_H__ #endif // __AP_HAL_EMPTY_CLASS_H__

View File

@ -3,15 +3,36 @@
using namespace Empty; using namespace Empty;
EmptySPIDeviceDriver::EmptySPIDeviceDriver() {} EmptySPIDeviceDriver::EmptySPIDeviceDriver()
void EmptySPIDeviceDriver::init() {} {}
AP_HAL::Semaphore* EmptySPIDeviceDriver::get_semaphore() {}
void EmptySPIDeviceDriver::cs_assert() {} void EmptySPIDeviceDriver::init()
void EmptySPIDeviceDriver::cs_release() {} {}
uint8_t EmptySPIDeviceDriver::transfer (uint8_t data) {return 0;}
AP_HAL::Semaphore* EmptySPIDeviceDriver::get_semaphore()
{
return &_semaphore;
}
void EmptySPIDeviceDriver::cs_assert()
{}
void EmptySPIDeviceDriver::cs_release()
{}
uint8_t EmptySPIDeviceDriver::transfer (uint8_t data)
{
return 0;
}
EmptySPIDeviceManager::EmptySPIDeviceManager()
{}
void EmptySPIDeviceManager::init(void *)
{}
EmptySPIDeviceManager::EmptySPIDeviceManager() {}
void EmptySPIDeviceManager::init(void *) {}
AP_HAL::SPIDeviceDriver* EmptySPIDeviceManager::device(enum AP_HAL::SPIDevice) AP_HAL::SPIDeviceDriver* EmptySPIDeviceManager::device(enum AP_HAL::SPIDevice)
{return &_device;} {
return &_device;
}

View File

@ -3,7 +3,7 @@
#define __AP_HAL_EMPTY_SPIDRIVER_H__ #define __AP_HAL_EMPTY_SPIDRIVER_H__
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty.h>
#include "Semaphore.h"
class Empty::EmptySPIDeviceDriver : public AP_HAL::SPIDeviceDriver { class Empty::EmptySPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
public: public:
@ -13,6 +13,8 @@ public:
void cs_assert(); void cs_assert();
void cs_release(); void cs_release();
uint8_t transfer (uint8_t data); uint8_t transfer (uint8_t data);
private:
EmptySemaphore _semaphore;
}; };
class Empty::EmptySPIDeviceManager : public AP_HAL::SPIDeviceManager { class Empty::EmptySPIDeviceManager : public AP_HAL::SPIDeviceManager {

View File

@ -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;
}

View File

@ -5,7 +5,18 @@
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty.h>
class Empty::EmptySemaphore : public AP_HAL::Semaphore { class Empty::EmptySemaphore : public AP_HAL::Semaphore {
public:
EmptySemaphore();
// get - to claim ownership of the semaphore
bool get(void* owner);
// release - to give up ownership of the semaphore
bool release(void* owner);
// call_on_release - returns true if caller successfully added to the
// queue to be called back
bool call_on_release(void* caller, AP_HAL::Proc k);
private:
void* _owner;
AP_HAL::Proc _k;
}; };
#endif // __AP_HAL_EMPTY_SEMAPHORE_H__ #endif // __AP_HAL_EMPTY_SEMAPHORE_H__

View File

@ -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)
{}

View File

@ -5,7 +5,18 @@
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty.h>
class Empty::EmptyStorage : public AP_HAL::Storage { class Empty::EmptyStorage : public AP_HAL::Storage {
public:
EmptyStorage();
void init(void *);
uint8_t read_byte(uint16_t loc);
uint16_t read_word(uint16_t loc);
uint32_t read_dword(uint16_t loc);
void read_block(void *dst, uint16_t src, size_t n);
void write_byte(uint16_t loc, uint8_t value);
void write_word(uint16_t loc, uint16_t value);
void write_dword(uint16_t loc, uint32_t value);
void write_block(uint16_t dst, void* src, size_t n);
}; };
#endif // __AP_HAL_EMPTY_STORAGE_H__ #endif // __AP_HAL_EMPTY_STORAGE_H__