mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
Implement the missing AP_Var_group::*serialize functions.
Rather than implementing empty default constructors, make sure that AP_Var and friends have useful default constructors instead. This works around AP_Meta_class::meta_cast requiring a default constructor without having empty ctors scattered around. Add accessors to AP_Var so that the global variable list can be traversed and the group/variable relationship comprehended by outsiders. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1523 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
d53844c52d
commit
6cf396074b
@ -25,14 +25,6 @@ int AP_Var::_lookup_hint_index = 0;
|
||||
uint16_t AP_Var::_tail_sentinel;
|
||||
bool AP_Var::_EEPROM_scanned;
|
||||
|
||||
AP_Var_group::AP_Var_group()
|
||||
{
|
||||
}
|
||||
|
||||
AP_Var_group::~AP_Var_group()
|
||||
{
|
||||
}
|
||||
|
||||
// Constructor
|
||||
//
|
||||
AP_Var::AP_Var(Key key, const prog_char *name, AP_Var_group *group, Flags flags) :
|
||||
@ -442,3 +434,59 @@ bool AP_Var::_EEPROM_locate(bool allocate)
|
||||
return true;
|
||||
}
|
||||
|
||||
size_t
|
||||
AP_Var_group::serialize(void *buf, size_t buf_size)
|
||||
{
|
||||
return _serialize_unserialize(buf, buf_size, true);
|
||||
}
|
||||
|
||||
size_t
|
||||
AP_Var_group::unserialize(void *buf, size_t buf_size)
|
||||
{
|
||||
return _serialize_unserialize(buf, buf_size, false);
|
||||
}
|
||||
|
||||
size_t
|
||||
AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_serialize)
|
||||
{
|
||||
AP_Var *vp;
|
||||
uint8_t *bp;
|
||||
size_t size, total_size, resid;
|
||||
|
||||
// Traverse the list of group members, serializing each in order
|
||||
//
|
||||
vp = next();
|
||||
bp = (uint8_t *)buf;
|
||||
resid = buf_size;
|
||||
total_size = 0;
|
||||
while (vp->group() == this) {
|
||||
|
||||
// (un)serialise the group member
|
||||
if (do_serialize) {
|
||||
size = vp->serialize(bp, buf_size);
|
||||
} else {
|
||||
size = vp->unserialize(bp, buf_size);
|
||||
}
|
||||
|
||||
// Account for the space that this variable consumes in the buffer
|
||||
//
|
||||
// We always count the total size, and we always advance the buffer pointer
|
||||
// if there was room for the variable. This does mean that in the case where
|
||||
// the buffer was too small for a variable in the middle of the group, that
|
||||
// a smaller variable after it in the group may still be serialised into
|
||||
// the buffer. Since that's a rare case it's not worth optimising for - in
|
||||
// either case this function will return a size greater than the buffer size
|
||||
// and the calling function will have to treat it as an error.
|
||||
//
|
||||
total_size += size;
|
||||
if (size <= resid) {
|
||||
// there was space for this one, account for it
|
||||
resid -= size;
|
||||
bp += size;
|
||||
}
|
||||
|
||||
vp = vp->next();
|
||||
}
|
||||
return total_size;
|
||||
}
|
||||
|
||||
|
@ -128,8 +128,6 @@ public:
|
||||
k_no_import = (1 << 1)
|
||||
};
|
||||
|
||||
AP_Var() {}
|
||||
|
||||
/// Constructor
|
||||
///
|
||||
/// @param key The storage key to be associated with this variable.
|
||||
@ -140,7 +138,7 @@ public:
|
||||
/// by ::copy_name.
|
||||
/// @param flags Optional flags which control how the variable behaves.
|
||||
///
|
||||
AP_Var(Key key, const prog_char *name, AP_Var_group *group, Flags flags);
|
||||
AP_Var(Key key = k_no_key, const prog_char *name = NULL, AP_Var_group *group = NULL, Flags flags = k_no_flags);
|
||||
|
||||
/// Destructor
|
||||
///
|
||||
@ -237,11 +235,25 @@ public:
|
||||
return (_flags & flagval) == flagval;
|
||||
}
|
||||
|
||||
/// Returns the group that a variable belongs to
|
||||
///
|
||||
/// @return The parent group, or NULL if the variable is not grouped.
|
||||
///
|
||||
AP_Var_group *group(void) { return _group; }
|
||||
|
||||
/// Returns the next variable in the global list
|
||||
///
|
||||
/// @return The next variable, either the next group member in order or
|
||||
/// the next variable in an arbitrary order, or NULL if this is
|
||||
/// the last variable in the list.
|
||||
///
|
||||
AP_Var *next(void) { return _link; }
|
||||
|
||||
private:
|
||||
AP_Var_group *_group; ///< Group that the variable may be a member of
|
||||
AP_Var *_link; ///< linked list pointer to next variable
|
||||
Key _key; ///< storage key
|
||||
const prog_char *_name; ///< name known to external agents (GCS, etc.)
|
||||
AP_Var *_link; ///< linked list pointer to next variable
|
||||
uint8_t _flags; ///< flag bits
|
||||
|
||||
// static state used by ::lookup
|
||||
@ -308,15 +320,12 @@ private:
|
||||
class AP_Var_group : public AP_Var
|
||||
{
|
||||
public:
|
||||
AP_Var_group();
|
||||
virtual ~AP_Var_group();
|
||||
|
||||
/// Constructor
|
||||
///
|
||||
/// @param key Storage key for the group.
|
||||
/// @param name An optional name prefix for members of the group.
|
||||
///
|
||||
AP_Var_group(Key key, const prog_char *name = NULL) :
|
||||
AP_Var_group(Key key = k_no_key, const prog_char *name = NULL) :
|
||||
AP_Var(key, name, NULL, k_no_flags)
|
||||
{
|
||||
}
|
||||
@ -326,23 +335,39 @@ public:
|
||||
/// Iteratively serializes the entire group into the supplied buffer.
|
||||
///
|
||||
/// @param buf Buffer into which serialized data should be placed.
|
||||
/// @param bufSize The size of the buffer provided.
|
||||
/// @param buf_size The size of the buffer provided.
|
||||
/// @return The size of the serialized data, even if that data would
|
||||
/// have overflowed the buffer.
|
||||
/// 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 bufSize) const;
|
||||
virtual size_t serialize(void *buf, size_t buf_size);
|
||||
|
||||
/// Unserialize the group.
|
||||
///
|
||||
/// Iteratively unserializes the group from the supplied buffer.
|
||||
///
|
||||
/// @param buf Buffer containing serialized data.
|
||||
/// @param bufSize The size of the buffer.
|
||||
/// @param buf_size The size of the buffer.
|
||||
/// @return The number of bytes from the buffer that would be consumed
|
||||
/// unserializing the data. If the value is less than or equal
|
||||
/// to bufSize, unserialization was successful.
|
||||
/// to buf_size, unserialization was successful.
|
||||
///
|
||||
virtual size_t unserialize(void *buf, size_t bufSize);
|
||||
virtual size_t unserialize(void *buf, size_t buf_size);
|
||||
|
||||
private:
|
||||
/// Common implementation of the group member traversal and accounting used
|
||||
/// by serialize/unserialize.
|
||||
///
|
||||
/// @param buf Buffer containing serialized data.
|
||||
/// @param buf_size The size of the buffer.
|
||||
/// @param do_serialize True if the operation should serialize, false if it should
|
||||
/// unserialize.
|
||||
/// @return The number of bytes from the buffer that would be consumed
|
||||
/// 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);
|
||||
|
||||
};
|
||||
|
||||
@ -390,7 +415,7 @@ public:
|
||||
///
|
||||
AP_VarT<T> (AP_Var_group *group,
|
||||
Key index,
|
||||
T initial_value = 0,
|
||||
T initial_value,
|
||||
const prog_char *name = NULL,
|
||||
Flags flags = k_no_flags) :
|
||||
AP_Var(index, name, group, flags),
|
||||
|
@ -64,9 +64,9 @@ setup(void)
|
||||
{
|
||||
TEST(meta_type_id);
|
||||
|
||||
AP_Float f1;
|
||||
AP_Float f2;
|
||||
AP_Int8 i1;
|
||||
AP_Float f1(0);
|
||||
AP_Float f2(0);
|
||||
AP_Int8 i1(0);
|
||||
|
||||
uint16_t m1 = f1.meta_type_id();
|
||||
uint16_t m2 = f2.meta_type_id();
|
||||
@ -77,13 +77,17 @@ setup(void)
|
||||
REQUIRE(m1 != m3);
|
||||
REQUIRE(AP_Meta_class::meta_type_equivalent(&f1, &f2));
|
||||
REQUIRE(!AP_Meta_class::meta_type_equivalent(&f1, &i1));
|
||||
|
||||
REQUIRE(NULL != AP_Meta_class::meta_cast<AP_Float>(&f1));
|
||||
REQUIRE(NULL == AP_Meta_class::meta_cast<AP_Int8>(&f1));
|
||||
REQUIRE(NULL == AP_Meta_class::meta_cast<AP_Float16>(&f1));
|
||||
}
|
||||
|
||||
// MetaClass: test external handles
|
||||
{
|
||||
TEST(meta_handle);
|
||||
|
||||
AP_Float f;
|
||||
AP_Float f(0);
|
||||
AP_Meta_class::Meta_handle h = f.meta_get_handle();
|
||||
|
||||
REQUIRE(0 != h);
|
||||
@ -95,7 +99,7 @@ setup(void)
|
||||
{
|
||||
TEST(meta_cast);
|
||||
|
||||
AP_Float f;
|
||||
AP_Float f(0);
|
||||
|
||||
REQUIRE(NULL != AP_Meta_class::meta_cast<AP_Float>(&f));
|
||||
REQUIRE(NULL == AP_Meta_class::meta_cast<AP_Int8>(&f));
|
||||
|
Loading…
Reference in New Issue
Block a user