AP_HAL_Empty: started building out the scaffolding

This commit is contained in:
Pat Hickey 2012-12-14 17:55:38 -08:00 committed by Andrew Tridgell
parent b79bd01761
commit 3e3c0f57ae
26 changed files with 480 additions and 0 deletions

View File

@ -0,0 +1,34 @@
#ifndef __AP_HAL_EMPTY_H__
#define __AP_HAL_EMPTY_H__
/* Your layer exports should depend on AP_HAL.h ONLY. */
#include <AP_HAL.h>
/**
* Umbrella header for AP_HAL_Empty module.
* The module header exports singleton instances which must conform the
* AP_HAL::HAL interface. It may only expose implementation details (class
* names, headers) via the Empty namespace.
* The class implementing AP_HAL::HAL should be called HAL_Empty and exist
* in the global namespace. There should be a single const instance of the
* HAL_Empty class called AP_HAL_Empty, instantiated in the HAL_Empty_Class.cpp
* and exported as `extern const HAL_Empty AP_HAL_Empty;` in HAL_Empty_Class.h
*
* All declaration and compilation should be guarded by CONFIG_HAL_BOARD macros.
* In this case, we're using CONFIG_HAL_BOARD == HAL_BOARD_EMPTY.
* When creating a new HAL, declare a new HAL_BOARD_ in AP_HAL/AP_HAL_Boards.h
*
* The module should also export an appropriate AP_HAL_MAIN() macro iff the
* appropriate CONFIG_HAL_BOARD value is set.
* The AP_HAL_MAIN macro expands to a main function (either an `int main (void)`
* or `int main (int argc, const char * argv[]), depending on platform) of an
* ArduPilot application, whose entry points are the c++ functions
* `void setup()` and `void loop()`, ala Arduino.
*/
#include "HAL_Empty_Class.h"
#include "AP_HAL_Empty_Main.h"
#endif //__AP_HAL_EMPTY_H__

View File

@ -0,0 +1,17 @@
#ifndef __AP_HAL_EMPTY_MAIN_H__
#define __AP_HAL_EMPTY_MAIN_H__
#if CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
#define AP_HAL_MAIN() extern "C" {\
int main (void) {\
hal.init(0, NULL); \
setup();\
for(;;) loop();\
return 0;\
}\
}
#endif // HAL_BOARD_EMPTY
#endif // __AP_HAL_EMPTY_MAIN_H__

View File

@ -0,0 +1,29 @@
#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 {
class EmptyUARTDriver;
class EmptyI2CDriver;
class EmptySPIDeviceManager;
class EmptySPIDeviceDriver;
class EmptyAnalogSource;
class EmptyAnalogIn;
class EmptyStorage;
class EmptyConsoleDriver;
class EmptyGPIO;
class EmptyDigitalSource;
class EmptyRCInput;
class EmptyRCOutput;
class EmptySemaphore;
class EmptyScheduler;
class EmptyPrivateMember;
}
#endif // __AP_HAL_EMPTY_NAMESPACE_H__

View File

@ -0,0 +1,23 @@
#ifndef __AP_HAL_EMPTY_PRIVATE_H__
#define __AP_HAL_EMPTY_PRIVATE_H__
/* Umbrella header for all private headers of the AP_HAL_Empty module.
* Only import this header from inside AP_HAL_Empty
*/
#include "UARTDriver.h"
#include "I2CDriver.h"
#include "SPIDriver.h"
#include "AnalogIn.h"
#include "Storage.h"
#include "Console.h"
#include "GPIO.h"
#include "RCInput.h"
#include "RCOutput.h"
#include "Semaphore.h"
#include "Scheduler.h"
#include "PrivateMember.h"
#endif // __AP_HAL_EMPTY_PRIVATE_H__

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_EMPTY_ANALOGIN_H__
#define __AP_HAL_EMPTY_ANALOGIN_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyAnalogIn : public AP_HAL::AnalogIn {
};
#endif // __AP_HAL_EMPTY_ANALOGIN_H__

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_EMPTY_CONSOLE_H__
#define __AP_HAL_EMPTY_CONSOLE_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyConsoleDriver : public AP_HAL::ConsoleDriver {
};
#endif // __AP_HAL_EMPTY_CONSOLE_H__

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_EMPTY_GPIO_H__
#define __AP_HAL_EMPTY_GPIO_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyGPIO : public AP_HAL::GPIO {
};
#endif // __AP_HAL_EMPTY_GPIO_H__

View File

@ -0,0 +1,47 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
#include "HAL_Empty_Class.h"
#include "AP_HAL_Empty_Private.h"
using namespace Empty;
static EmptyUARTDriver uartADriver;
static EmptyUARTDriver uartBDriver;
static EmptyUARTDriver uartCDriver;
static EmptyI2CDriver i2cDriver;
static EmptySPIDeviceManager spiDeviceManager;
static EmptyAnalogIn analogIn;
static EmptyStorage storageDriver;
static EmptyGPIO gpioDriver;
static EmptyRCInput rcinDriver;
static EmptyRCOutput rcoutDriver;
static EmptyScheduler scheduler;
HAL_Empty::HAL_Empty() :
AP_HAL::HAL(
&uartADriver,
&uartBDriver,
&uartCDriver,
&i2cDriver,
&spiDeviceManager,
&analogIn,
&storageDriver,
&gpioDriver,
&rcinDriver,
&rcoutDriver,
&scheduler ),
_priv(new EmptyPrivateMember(123))
{}
void HAL_Empty::init(int argc, const char * argv[]) const {
uartA->init();
_priv->init();
}
const HAL_Empty AP_HAL_Empty;
#endif // CONFIG_HAL_BOARD == HAL_BOARD_EMPTY

View File

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

View File

@ -0,0 +1,27 @@
#include "I2CDriver.h"
using namespace Empty;
void EmptyI2CDriver::begin() {}
void EmptyI2CDriver::end() {}
void EmptyI2CDriver::setTimeout(uint16_t ms) {}
void EmptyI2CDriver::setHighSpeed(bool active) {}
uint8_t EmptyI2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
{return 0;}
uint8_t EmptyI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
{return 0;}
uint8_t EmptyI2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data)
{return 0;}
uint8_t EmptyI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
{return 0;}
uint8_t EmptyI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data)
{return 0;}
uint8_t EmptyI2CDriver::readRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data)
{return 0;}
uint8_t EmptyI2CDriver::lockup_count() {return 0;}

View File

@ -0,0 +1,35 @@
#ifndef __AP_HAL_EMPTY_I2CDRIVER_H__
#define __AP_HAL_EMPTY_I2CDRIVER_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyI2CDriver : public AP_HAL::I2CDriver {
void begin();
void end();
void setTimeout(uint16_t ms);
void setHighSpeed(bool active);
/* write: for i2c devices which do not obey register conventions */
uint8_t write(uint8_t addr, uint8_t len, uint8_t* data);
/* writeRegister: write a single 8-bit value to a register */
uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val);
/* writeRegisters: write bytes to contigious registers */
uint8_t writeRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data);
/* read: for i2c devices which do not obey register conventions */
uint8_t read(uint8_t addr, uint8_t len, uint8_t* data);
/* readRegister: read from a device register - writes the register,
* then reads back an 8-bit value. */
uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data);
/* readRegister: read contigious device registers - writes the first
* register, then reads back multiple bytes */
uint8_t readRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data);
uint8_t lockup_count();
};
#endif // __AP_HAL_EMPTY_I2CDRIVER_H__

View File

@ -0,0 +1,11 @@
#include "PrivateMember.h"
using namespace Empty;
EmptyPrivateMember::EmptyPrivateMember(uint16_t foo) :
_foo(foo)
{}
void EmptyPrivateMember::init() {}

View File

@ -0,0 +1,19 @@
#ifndef __AP_HAL_EMPTY_PRIVATE_MEMBER_H__
#define __AP_HAL_EMPTY_PRIVATE_MEMBER_H__
/* Just a stub as an example of how to implement a private member of an
* AP_HAL module */
#include "AP_HAL_Empty.h"
class Empty::EmptyPrivateMember {
public:
EmptyPrivateMember(uint16_t foo);
void init();
private:
uint16_t _foo;
};
#endif // __AP_HAL_EMPTY_PRIVATE_MEMBER_H__

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_EMPTY_RCINPUT_H__
#define __AP_HAL_EMPTY_RCINPUT_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyRCInput : public AP_HAL::RCInput {
};
#endif // __AP_HAL_EMPTY_RCINPUT_H__

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_EMPTY_RCOUTPUT_H__
#define __AP_HAL_EMPTY_RCOUTPUT_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyRCOutput : public AP_HAL::RCOutput {
};
#endif // __AP_HAL_EMPTY_RCOUTPUT_H__

View File

@ -0,0 +1,17 @@
#include "SPIDriver.h"
using namespace Empty;
EmptySPIDeviceDriver::EmptySPIDeviceDriver() {}
void EmptySPIDeviceDriver::init() {}
AP_HAL::Semaphore* EmptySPIDeviceDriver::get_semaphore() {}
void EmptySPIDeviceDriver::cs_assert() {}
void EmptySPIDeviceDriver::cs_release() {}
uint8_t EmptySPIDeviceDriver::transfer (uint8_t data) {return 0;}
EmptySPIDeviceManager::EmptySPIDeviceManager() {}
void EmptySPIDeviceManager::init(void *) {}
AP_HAL::SPIDeviceDriver* EmptySPIDeviceManager::device(enum AP_HAL::SPIDevice)
{return &_device;}

View File

@ -0,0 +1,27 @@
#ifndef __AP_HAL_EMPTY_SPIDRIVER_H__
#define __AP_HAL_EMPTY_SPIDRIVER_H__
#include <AP_HAL_Empty.h>
class Empty::EmptySPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
public:
EmptySPIDeviceDriver();
void init();
AP_HAL::Semaphore* get_semaphore();
void cs_assert();
void cs_release();
uint8_t transfer (uint8_t data);
};
class Empty::EmptySPIDeviceManager : public AP_HAL::SPIDeviceManager {
public:
EmptySPIDeviceManager();
void init(void *);
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice);
private:
EmptySPIDeviceDriver _device;
};
#endif // __AP_HAL_EMPTY_SPIDRIVER_H__

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_EMPTY_SCHEDULER_H__
#define __AP_HAL_EMPTY_SCHEDULER_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyScheduler : public AP_HAL::Scheduler {
};
#endif // __AP_HAL_EMPTY_SCHEDULER_H__

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_EMPTY_SEMAPHORE_H__
#define __AP_HAL_EMPTY_SEMAPHORE_H__
#include <AP_HAL_Empty.h>
class Empty::EmptySemaphore : public AP_HAL::Semaphore {
};
#endif // __AP_HAL_EMPTY_SEMAPHORE_H__

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_EMPTY_STORAGE_H__
#define __AP_HAL_EMPTY_STORAGE_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyStorage : public AP_HAL::Storage {
};
#endif // __AP_HAL_EMPTY_STORAGE_H__

View File

@ -0,0 +1,30 @@
#include "UARTDriver.h"
using namespace Empty;
EmptyUARTDriver::EmptyUARTDriver() {}
void EmptyUARTDriver::begin(uint32_t b) {}
void EmptyUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) {}
void EmptyUARTDriver::end() {}
void EmptyUARTDriver::flush() {}
bool EmptyUARTDriver::is_initialized() { return false; }
void EmptyUARTDriver::set_blocking_writes(bool blocking) {}
bool EmptyUARTDriver::tx_pending() { return false; }
/* Empty implementations of BetterStream virtual methods */
void EmptyUARTDriver::print_P(const prog_char_t *pstr) {}
void EmptyUARTDriver::println_P(const prog_char_t *pstr) {}
void EmptyUARTDriver::printf(const char *pstr, ...) {}
void EmptyUARTDriver::_printf_P(const prog_char *pstr, ...) {}
/* Empty implementations of Stream virtual methods */
int16_t EmptyUARTDriver::available() { return 0; }
int16_t EmptyUARTDriver::txspace() { return 1; }
int16_t EmptyUARTDriver::read() { return -1; }
int16_t EmptyUARTDriver::peek() { return -1; }
/* Empty implementations of Print virtual methods */
size_t EmptyUARTDriver::write(uint8_t c) { return 0; }

View File

@ -0,0 +1,35 @@
#ifndef __AP_HAL_EMPTY_UARTDRIVER_H__
#define __AP_HAL_EMPTY_UARTDRIVER_H__
#include <AP_HAL_Empty.h>
class Empty::EmptyUARTDriver : public AP_HAL::UARTDriver {
public:
EmptyUARTDriver();
/* Empty implementations of UARTDriver virtual methods */
void begin(uint32_t b);
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
void end();
void flush();
bool is_initialized();
void set_blocking_writes(bool blocking);
bool tx_pending();
/* Empty implementations of BetterStream virtual methods */
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, ...);
/* Empty implementations of Stream virtual methods */
int16_t available();
int16_t txspace();
int16_t read();
int16_t peek();
/* Empty implementations of Print virtual methods */
size_t write(uint8_t c);
};
#endif // __AP_HAL_EMPTY_UARTDRIVER_H__

View File

@ -0,0 +1 @@
include ../../../AP_Common/Arduino.mk

View File

@ -0,0 +1,16 @@
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AP_HAL.h>
#include <AP_HAL_Empty.h>
extern const AP_HAL::HAL& hal;// = AP_HAL_Empty;
void setup() {}
void loop() {}
AP_HAL_MAIN();