Increase the maximum save size to 64B, so that a Vector3f can be saved.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1704 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok@gmail.com 2011-02-21 04:42:28 +00:00
parent 5282c72d1f
commit 94537aa143
2 changed files with 5 additions and 6 deletions

View File

@ -522,7 +522,6 @@ bool AP_Var::_EEPROM_locate(bool allocate)
// If not located and not permitted to allocate, we have failed.
//
if (!allocate) {
debug("cannot allocate");
return false;
}
debug("needs allocation");

View File

@ -45,7 +45,7 @@ public:
};
static const uint16_t k_EEPROM_magic = 0x5041; ///< "AP"
static const uint16_t k_EEPROM_revision = 1; ///< current format revision
static const uint16_t k_EEPROM_revision = 2; ///< current format revision
/// Storage key for variables that are saved in EEPROM.
///
@ -72,15 +72,15 @@ public:
///
struct Var_header {
/// The size of the variable, minus one.
/// This allows a variable or group to be anything from one to 32 bytes long.
/// This allows a variable or group to be anything from one to 64 bytes long.
///
uint8_t size:5;
uint8_t size:6;
/// Spare bits, currently unused
///
/// @todo One could be a parity bit?
///
uint8_t spare:3;
uint8_t spare:2;
/// The key assigned to the variable.
///
@ -122,7 +122,7 @@ public:
/// ::save_all and ::load_all functions. It should match the maximum size that can
/// be encoded in the Var_header::size field.
///
static const size_t k_size_max = 32;
static const size_t k_size_max = 64;
/// Optional flags affecting the behavior and usage of the variable.
///