mirror of https://github.com/ArduPilot/ardupilot
Fix ::save_all/::load_all so that they check the correct criteria for opt-out. Now load/save_all work.
Fix prototype for AP_Var_group::serialize so that it's called correctly when saving a group. Now group load/save works. Add load/save_all and group load/save unit tests. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1533 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
3adec05593
commit
82fdeb11bb
|
@ -204,17 +204,17 @@ bool AP_Var::load(void)
|
|||
bool AP_Var::save_all(void)
|
||||
{
|
||||
bool result = true;
|
||||
AP_Var *p = _variables;
|
||||
AP_Var *vp = _variables;
|
||||
|
||||
while (p) {
|
||||
if (!p->has_flags(k_flag_no_auto_load) && // not opted out
|
||||
!(p->_group)) { // not saved with a group
|
||||
while (vp) {
|
||||
if (!vp->has_flags(k_flag_no_auto_load) && // not opted out of autosave
|
||||
(vp->_key != k_key_none)) { // has a key
|
||||
|
||||
if (!p->save()) {
|
||||
if (!vp->save()) {
|
||||
result = false;
|
||||
}
|
||||
}
|
||||
p = p->_link;
|
||||
vp = vp->_link;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
@ -223,18 +223,18 @@ bool AP_Var::save_all(void)
|
|||
//
|
||||
bool AP_Var::load_all(void)
|
||||
{
|
||||
bool result;
|
||||
AP_Var *p = _variables;
|
||||
bool result = true;
|
||||
AP_Var *vp = _variables;
|
||||
|
||||
while (p) {
|
||||
if (!p->has_flags(k_flag_no_auto_load) && // not opted out
|
||||
!(p->_group)) { // not loaded with a group
|
||||
while (vp) {
|
||||
if (!vp->has_flags(k_flag_no_auto_load) && // not opted out of autoload
|
||||
(vp->_key != k_key_none)) { // has a key
|
||||
|
||||
if (!p->load()) {
|
||||
if (!vp->load()) {
|
||||
result = false;
|
||||
}
|
||||
}
|
||||
p = p->_link;
|
||||
vp = vp->_link;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
@ -321,7 +321,9 @@ AP_Var::first_member(AP_Var_group *group)
|
|||
|
||||
vp = &_grouped_variables;
|
||||
|
||||
log("seeking %p", group);
|
||||
while (*vp) {
|
||||
log("consider %p with %p", *vp, (*vp)->_group);
|
||||
if ((*vp)->_group == group) {
|
||||
return *vp;
|
||||
}
|
||||
|
@ -412,7 +414,7 @@ bool AP_Var::_EEPROM_scan(void)
|
|||
vp = vp->_link;
|
||||
}
|
||||
if (!vp) {
|
||||
log("key %u not claimed", var_header.key);
|
||||
log("key %u not claimed (already scanned or unknown)", var_header.key);
|
||||
}
|
||||
|
||||
// move to the next variable header
|
||||
|
@ -460,13 +462,13 @@ bool AP_Var::_EEPROM_locate(bool allocate)
|
|||
if (!(_key & k_key_not_located)) {
|
||||
return true; // it has
|
||||
}
|
||||
|
||||
// If not located and not permitted to allocate, we have failed.
|
||||
//
|
||||
if (!allocate) {
|
||||
log("not found, cannot allocate");
|
||||
log("cannot allocate");
|
||||
return false;
|
||||
}
|
||||
log("needs allocation");
|
||||
|
||||
// Ask the serializer for the size of the thing we are allocating, and fail
|
||||
// if it is too large or if it has no size, as we will not be able to allocate
|
||||
|
@ -530,9 +532,12 @@ bool AP_Var::_EEPROM_locate(bool allocate)
|
|||
}
|
||||
|
||||
size_t
|
||||
AP_Var_group::serialize(void *buf, size_t buf_size)
|
||||
AP_Var_group::serialize(void *buf, size_t buf_size) const
|
||||
{
|
||||
return _serialize_unserialize(buf, buf_size, true);
|
||||
// We have to cast away the const in order to call _serialize_unserialize,
|
||||
// as it cannot be const due to changing this when called to unserialize.
|
||||
//
|
||||
return const_cast<AP_Var_group *>(this)->_serialize_unserialize(buf, buf_size, true);
|
||||
}
|
||||
|
||||
size_t
|
||||
|
@ -551,6 +556,7 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali
|
|||
// Traverse the list of group members, serializing each in order
|
||||
//
|
||||
vp = first_member(this);
|
||||
log("starting with %p", vp);
|
||||
bp = (uint8_t *)buf;
|
||||
resid = buf_size;
|
||||
total_size = 0;
|
||||
|
@ -559,8 +565,10 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali
|
|||
// (un)serialise the group member
|
||||
if (do_serialize) {
|
||||
size = vp->serialize(bp, buf_size);
|
||||
log("serialize %p -> %u", vp, size);
|
||||
} else {
|
||||
size = vp->unserialize(bp, buf_size);
|
||||
log("unserialize %p -> %u", vp, size);
|
||||
}
|
||||
|
||||
// Account for the space that this variable consumes in the buffer
|
||||
|
@ -574,6 +582,7 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali
|
|||
// and the calling function will have to treat it as an error.
|
||||
//
|
||||
total_size += size;
|
||||
log("used %u", total_size);
|
||||
if (size <= resid) {
|
||||
// there was space for this one, account for it
|
||||
resid -= size;
|
||||
|
@ -584,4 +593,3 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali
|
|||
}
|
||||
return total_size;
|
||||
}
|
||||
|
||||
|
|
|
@ -301,7 +301,7 @@ public:
|
|||
|
||||
/// Returns the next variable that is a member of the same group.
|
||||
///
|
||||
/// This does not behave correctly if called on a variable that is not a group member.
|
||||
/// This will not behave correctly if called on a variable that is not a group member.
|
||||
///
|
||||
/// @param group The group whose member(s) are sought.
|
||||
/// @return The next variable in the group, or NULL if there are none.
|
||||
|
@ -310,7 +310,8 @@ public:
|
|||
|
||||
/// Returns the storage key for a variable.
|
||||
///
|
||||
/// Note that group members do not have storage keys - the key is held by the group.
|
||||
/// Note that group members do not have storage keys - the key is held by the group
|
||||
/// and instead the key indicates the variable's ordering within the group.
|
||||
///
|
||||
/// @return The variable's key, or k_key_none if it does not have a key.
|
||||
///
|
||||
|
@ -390,7 +391,7 @@ public:
|
|||
/// have overflowed the buffer. If the value is less than or
|
||||
/// equal to buf_size, serialization was successful.
|
||||
///
|
||||
virtual size_t serialize(void *buf, size_t buf_size);
|
||||
virtual size_t serialize(void *buf, size_t buf_size) const;
|
||||
|
||||
/// Unserialize the group.
|
||||
///
|
||||
|
@ -416,7 +417,6 @@ private:
|
|||
/// operating on the data. If the value is less than or equal
|
||||
/// to buf_size, the operation was successful.
|
||||
///
|
||||
|
||||
size_t _serialize_unserialize(void *buf, size_t buf_size, bool do_serialize);
|
||||
};
|
||||
|
||||
|
|
|
@ -291,14 +291,53 @@ setup(void)
|
|||
|
||||
// AP_Var: reload
|
||||
{
|
||||
TEST(reload);
|
||||
TEST(var_reload);
|
||||
|
||||
AP_Float f1(0, 1);
|
||||
|
||||
REQUIRE(true == f1.load());
|
||||
REQUIRE(f1 == 10.0);
|
||||
|
||||
AP_Var::erase_all();
|
||||
}
|
||||
|
||||
// AP_Var: save/load all
|
||||
{
|
||||
TEST(var_save_load_all);
|
||||
|
||||
AP_Float f1(10.0, 1);
|
||||
AP_Float f2(123.0, 2);
|
||||
|
||||
REQUIRE(true == AP_Var::save_all());
|
||||
f1 = 0;
|
||||
f2 = 0;
|
||||
REQUIRE(true == AP_Var::load_all());
|
||||
REQUIRE(f1 == 10.0);
|
||||
REQUIRE(f2 == 123.0);
|
||||
|
||||
AP_Var::erase_all();
|
||||
}
|
||||
|
||||
// AP_Var: group load/save
|
||||
{
|
||||
TEST(var_group_save_load);
|
||||
|
||||
AP_Var_group group(10);
|
||||
AP_Float f1(&group, 0, 10.0);
|
||||
AP_Float f2(&group, 0, 123.0);
|
||||
AP_Float f3(-1.0);
|
||||
|
||||
REQUIRE(true == group.save());
|
||||
f1 = 0;
|
||||
f2 = 0;
|
||||
f3 = 0;
|
||||
REQUIRE(true == group.load());
|
||||
REQUIRE(f1 == 10.0);
|
||||
REQUIRE(f2 == 123.0);
|
||||
REQUIRE(f3 == 0);
|
||||
|
||||
AP_Var::erase_all();
|
||||
}
|
||||
|
||||
#if SAVE
|
||||
// AP_Var: load and save
|
||||
|
|
Loading…
Reference in New Issue