Removed conflicting AP_EEPROM library.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1240 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-12-23 23:27:04 +00:00
parent 125b971173
commit 7be8e77711
3 changed files with 0 additions and 182 deletions

View File

@ -1,67 +0,0 @@
/*
RC_Channel.cpp - Radio library for Arduino
Code by Jason Short. DIYDrones.com
This library is free software; you can redistribute it and / or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
*/
#include <avr/eeprom.h>
#include "AP_EEPROM.h"
//#include "WProgram.h"
void
AP_EEPROM::write_byte(int address, int8_t value)
{
eeprom_write_byte((uint8_t *) address, value);
}
void
AP_EEPROM::write_int(int address, int value)
{
eeprom_write_word((uint16_t *) address, value);
}
void
AP_EEPROM::write_long(int address, long value)
{
eeprom_write_dword((uint32_t *) address, value);
}
void
AP_EEPROM::write_float(int address, float value)
{
_type_union.fvalue = value;
write_long(address, _type_union.lvalue);
}
int
AP_EEPROM::read_byte(int address)
{
return eeprom_read_byte((const uint8_t *) address);
}
int
AP_EEPROM::read_int(int address)
{
return eeprom_read_word((const uint16_t *) address);
}
long
AP_EEPROM::read_long(int address)
{
return eeprom_read_dword((const uint32_t *) address);
}
float
AP_EEPROM::read_float(int address)
{
_type_union.lvalue = eeprom_read_dword((const uint32_t *) address);
return _type_union.fvalue;
}

View File

@ -1,82 +0,0 @@
#ifndef AP_EEProm_H
#define AP_EEProm_H
#include <AP_Vector.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
class AP_EEPromEntry
{
public:
virtual void setEntry(float val) = 0;
virtual float getEntry() = 0;
uint16_t getId() { return _id; }
uint16_t getAddress() { return _address; }
protected:
uint16_t _id;
uint16_t _address;
};
class AP_EEPromRegistry : public AP_Vector<AP_EEPromEntry *>
{
public:
/**
* Default constructor
*/
AP_EEPromRegistry(uint16_t maxSize) :
_lastAddress(0), _lastId(0), _maxSize(maxSize)
{
}
/**
* Add an entry to the registry
*/
void add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & address, size_t size)
{
if (_lastAddress + size > _maxSize) return;
address = _lastAddress;
_lastAddress += size;
id = _lastId++;
push_back(entry);
}
private:
uint16_t _lastAddress;
uint16_t _lastId;
uint16_t _maxSize;
};
AP_EEPromRegistry eepromRegistry(1024);
template <class type>
class AP_EEPromVar : public AP_EEPromEntry
{
public:
AP_EEPromVar()
{
eepromRegistry.add(this,_id,_address,sizeof(_data));
}
void set(type val) { _data = val; }
type get() { return _data; }
void save()
{
eeprom_write_block((const void*)&_data,(void*)(_address),sizeof(_data));
}
void load()
{
eeprom_read_block((void*)&_data,(const void*)(_address),sizeof(_data));
}
virtual void setEntry(float val)
{
_data = (type)val;
}
virtual float getEntry()
{
return (float)_data;
}
private:
type _data;
};
#endif

View File

@ -1,33 +0,0 @@
/*
* Libraries
*/
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_EEProm.h>
AP_EEPromVar<int> var;
FastSerialPort0(Serial);
void setup()
{
Serial.begin(115200);
Serial.println("starting");
displayMemory();
}
void loop()
{
var.set(123);
Serial.printf_P(PSTR("initially set 123 and save: %d\n"), var.get());
var.save();
var.set(456);
Serial.printf_P(PSTR("next set to 456: %d\n"), var.get());
var.load();
Serial.printf_P(PSTR("now reload initial value: %d\n"), var.get());
uint16_t id = var.getId();
Serial.printf_P(PSTR("now find id for variable: %d\n"), id);
Serial.printf_P(PSTR("now find variable value by id: %f\n"), eepromRegistry(id)->getEntry());
eepromRegistry(id)->setEntry(456);
Serial.printf_P(PSTR("now set variable value by id to 456: %d\n"), var.get());
delay(5000);
}