mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Fix AP_Var::load - it has to ask the serialiser, not the unserialiser, for the variable's size.
Fix AP_Float16 - scaling was being done in the wrong direction, and the unserialiser wasn't reporting errors. Add test cases for the above. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1696 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
3bf6257783
commit
d036cb9360
@ -72,7 +72,7 @@ AP_Var::AP_Var(AP_Var_group *group, Key index, const prog_char *name, Flags flag
|
|||||||
//
|
//
|
||||||
vp = &_grouped_variables;
|
vp = &_grouped_variables;
|
||||||
while (*vp != NULL) {
|
while (*vp != NULL) {
|
||||||
if ((*vp)->_key > _key) {
|
if ((*vp)->_key >= _key) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
vp = &((*vp)->_link);
|
vp = &((*vp)->_link);
|
||||||
@ -212,11 +212,11 @@ bool AP_Var::load(void)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// ask the unserializer how big the variable is
|
// ask the serializer how big the variable is
|
||||||
//
|
//
|
||||||
// XXX should check size in EEPROM var header too...
|
// XXX should check size in EEPROM var header too...
|
||||||
//
|
//
|
||||||
size = unserialize(NULL, 0);
|
size = serialize(NULL, 0);
|
||||||
|
|
||||||
// Read the buffer from EEPROM, now that _EEPROM_locate
|
// Read the buffer from EEPROM, now that _EEPROM_locate
|
||||||
// has converted _key into an EEPROM address.
|
// has converted _key into an EEPROM address.
|
||||||
@ -628,6 +628,8 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali
|
|||||||
debug("unserialize %p -> %u", vp, size);
|
debug("unserialize %p -> %u", vp, size);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// XXX HANDLE ERRORS HERE
|
||||||
|
|
||||||
// Account for the space that this variable consumes in the buffer
|
// Account for the space that this variable consumes in the buffer
|
||||||
//
|
//
|
||||||
// We always count the total size, and we always advance the buffer pointer
|
// We always count the total size, and we always advance the buffer pointer
|
||||||
|
@ -865,7 +865,7 @@ public:
|
|||||||
uint16_t *sval = (uint16_t *)buf;
|
uint16_t *sval = (uint16_t *)buf;
|
||||||
|
|
||||||
if (size >= sizeof(*sval)) {
|
if (size >= sizeof(*sval)) {
|
||||||
*sval = _value / 1024.0; // scale by power of 2, may be more efficient
|
*sval = _value * 1024.0; // scale by power of 2, may be more efficient
|
||||||
}
|
}
|
||||||
return sizeof(*sval);
|
return sizeof(*sval);
|
||||||
}
|
}
|
||||||
@ -876,9 +876,10 @@ public:
|
|||||||
uint16_t *sval = (uint16_t *)buf;
|
uint16_t *sval = (uint16_t *)buf;
|
||||||
|
|
||||||
if (size >= sizeof(*sval)) {
|
if (size >= sizeof(*sval)) {
|
||||||
_value = *sval * 1024.0; // scale by power of 2, may be more efficient
|
_value = (float)*sval / 1024.0; // scale by power of 2, may be more efficient
|
||||||
|
return sizeof(*sval);
|
||||||
}
|
}
|
||||||
return sizeof(*sval);
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// copy operators must be redefined in subclasses to get correct behavior
|
// copy operators must be redefined in subclasses to get correct behavior
|
||||||
|
@ -262,6 +262,7 @@ setup(void)
|
|||||||
TEST(var_save_load);
|
TEST(var_save_load);
|
||||||
|
|
||||||
AP_Float f1(10.0, 1);
|
AP_Float f1(10.0, 1);
|
||||||
|
AP_Float16 f2(1.23, 2);
|
||||||
|
|
||||||
AP_Var::erase_all();
|
AP_Var::erase_all();
|
||||||
REQUIRE(true == f1.save());
|
REQUIRE(true == f1.save());
|
||||||
@ -269,6 +270,13 @@ setup(void)
|
|||||||
f1 = 0;
|
f1 = 0;
|
||||||
REQUIRE(true == f1.load());
|
REQUIRE(true == f1.load());
|
||||||
REQUIRE(f1 == 10.0);
|
REQUIRE(f1 == 10.0);
|
||||||
|
|
||||||
|
REQUIRE(true == f2.save());
|
||||||
|
REQUIRE(f2 == 1.23);
|
||||||
|
f2 = 0;
|
||||||
|
REQUIRE(true == f2.load());
|
||||||
|
REQUIRE(f2 == 1.23);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// AP_Var: reload
|
// AP_Var: reload
|
||||||
@ -309,17 +317,20 @@ setup(void)
|
|||||||
|
|
||||||
AP_Var_group group(10);
|
AP_Var_group group(10);
|
||||||
AP_Float f1(&group, 0, 10.0);
|
AP_Float f1(&group, 0, 10.0);
|
||||||
AP_Float f2(&group, 0, 123.0);
|
AP_Float f2(&group, 1, 123.0);
|
||||||
AP_Float f3(-1.0);
|
AP_Float f3(-1.0);
|
||||||
|
AP_Float16 f4(&group, 2, 7);
|
||||||
|
|
||||||
REQUIRE(true == group.save());
|
REQUIRE(true == group.save());
|
||||||
f1 = 0;
|
f1 = 0;
|
||||||
f2 = 0;
|
f2 = 0;
|
||||||
f3 = 0;
|
f3 = 0;
|
||||||
|
f4 = 0;
|
||||||
REQUIRE(true == group.load());
|
REQUIRE(true == group.load());
|
||||||
REQUIRE(f1 == 10.0);
|
REQUIRE(f1 == 10.0);
|
||||||
REQUIRE(f2 == 123.0);
|
REQUIRE(f2 == 123.0);
|
||||||
REQUIRE(f3 == 0);
|
REQUIRE(f3 == 0);
|
||||||
|
REQUIRE(f4 == 7);
|
||||||
|
|
||||||
AP_Var::erase_all();
|
AP_Var::erase_all();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user