mirror of https://github.com/ArduPilot/ardupilot
EEPROM base class
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1238 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
36ade2aaf6
commit
b8ffddb061
|
@ -0,0 +1,67 @@
|
||||||
|
/*
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,41 @@
|
||||||
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||||
|
|
||||||
|
/// @file AP_EEPROM.h
|
||||||
|
/// @brief AP_EEPROM manager
|
||||||
|
|
||||||
|
#ifndef AP_EEPROM_h
|
||||||
|
#define AP_EEPROM_h
|
||||||
|
|
||||||
|
//#include <stdint.h>
|
||||||
|
#include "WProgram.h"
|
||||||
|
|
||||||
|
/// @class AP_EEPROM
|
||||||
|
/// @brief Object for reading and writing to the EEPROM
|
||||||
|
class AP_EEPROM{
|
||||||
|
public:
|
||||||
|
/// Constructor
|
||||||
|
AP_EEPROM(){}
|
||||||
|
|
||||||
|
int read_byte(int address);
|
||||||
|
int read_int(int address);
|
||||||
|
long read_long(int address);
|
||||||
|
float read_float(int address);
|
||||||
|
|
||||||
|
void write_byte(int address, int8_t value);
|
||||||
|
void write_int(int address, int16_t value);
|
||||||
|
void write_long(int address, int32_t value);
|
||||||
|
void write_float(int address, float value);
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
union type_union {
|
||||||
|
int8_t bytes[4];
|
||||||
|
long lvalue;
|
||||||
|
int ivalue;
|
||||||
|
float fvalue;
|
||||||
|
} _type_union;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -0,0 +1,39 @@
|
||||||
|
#include <AP_EEPROM.h> // ArduPilot Mega RC Library
|
||||||
|
|
||||||
|
byte byte_value = 99;
|
||||||
|
int int_value = 30000;
|
||||||
|
long long_value = 123456789;
|
||||||
|
float float_value = .01234;
|
||||||
|
|
||||||
|
AP_EEPROM ee;
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
Serial.begin(38400);
|
||||||
|
delay(100);
|
||||||
|
Serial.println("\nAP_EEPROM test");
|
||||||
|
|
||||||
|
Serial.println("AP_EEPROM test");
|
||||||
|
ee.write_byte(0, byte_value);
|
||||||
|
ee.write_int(1, int_value);
|
||||||
|
ee.write_long(3, long_value);
|
||||||
|
ee.write_float(7, float_value);
|
||||||
|
|
||||||
|
|
||||||
|
Serial.println(ee.read_byte(0), DEC);
|
||||||
|
Serial.println(ee.read_int(1), DEC);
|
||||||
|
Serial.println(ee.read_long(3), DEC);
|
||||||
|
float e = ee.read_float(7);
|
||||||
|
long y = e * 100;
|
||||||
|
//Serial.println(e, 5);930 bytes
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// 2162 bytes
|
||||||
|
// 2216
|
Loading…
Reference in New Issue