Add a little code to track the amount of memory used by AP_Var subclasses.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1661 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok@gmail.com 2011-02-16 07:01:17 +00:00
parent 6e0d023c95
commit f8f0027c7f
2 changed files with 24 additions and 2 deletions

View File

@ -28,12 +28,12 @@ AP_Float AP_Float_unity ( 1.0, AP_Var::k_key_none, NULL, AP_Var::k_flag_
AP_Float AP_Float_negative_unity(-1.0, AP_Var::k_key_none, NULL, AP_Var::k_flag_unlisted);
AP_Float AP_Float_zero ( 0.0, AP_Var::k_key_none, NULL, AP_Var::k_flag_unlisted);
// Static member variables for AP_Var.
//
AP_Var *AP_Var::_variables;
AP_Var *AP_Var::_grouped_variables;
uint16_t AP_Var::_tail_sentinel;
uint16_t AP_Var::_bytes_in_use;
// Constructor for standalone variables
//
@ -172,6 +172,8 @@ bool AP_Var::save(void)
return _group->save();
}
debug("save: %S", _name ? _name : PSTR("??"));
// locate the variable in EEPROM, allocating space as required
if (!_EEPROM_locate(true)) {
debug("locate failed");
@ -202,6 +204,8 @@ bool AP_Var::load(void)
return _group->load();
}
debug("load: %S", _name ? _name : PSTR("??"));
// locate the variable in EEPROM, but do not allocate space
if (!_EEPROM_locate(false)) {
debug("locate failed");

View File

@ -347,6 +347,16 @@ public:
///
virtual float cast_to_float() const;
/// Report the amount of memory being used by AP_Var subclasses.
///
/// @return The sum of sizeof(*this) for all constructed AP_Var subclass instances.
///
static uint16_t get_memory_use() { return _bytes_in_use; }
protected:
// Memory statistics
static uint16_t _bytes_in_use;
private:
AP_Var_group *_group; ///< Group that the variable may be a member of
AP_Var *_link; ///< linked list pointer to next variable
@ -363,7 +373,6 @@ private:
static const uint16_t k_EEPROM_size = 4096; ///< XXX avr-libc doesn't consistently export this
/// Scan the EEPROM and assign addresses to any known variables
/// that have entries there.
///
@ -409,6 +418,7 @@ public:
AP_Var_group(Key key = k_key_none, const prog_char *name = NULL, Flags flags = k_flags_none) :
AP_Var(key, name, flags | k_flag_is_group)
{
_bytes_in_use += sizeof(*this);
}
/// Serialize the group.
@ -478,6 +488,7 @@ public:
AP_Var(key, name, flags),
_value(initial_value)
{
_bytes_in_use += sizeof(*this);
}
/// Constructor for grouped variable.
@ -500,6 +511,7 @@ public:
AP_Var(group, index, name, flags),
_value(initial_value)
{
_bytes_in_use += sizeof(*this);
}
// serialize _value into the buffer, but only if it is big enough.
@ -608,6 +620,7 @@ public:
Flags flags = k_flags_none) :
AP_Var(key, name, flags)
{
_bytes_in_use += sizeof(*this);
}
/// Constructor for a grouped structure variable.
@ -627,6 +640,7 @@ public:
Flags flags = k_flags_none) :
AP_Var(group, index, name, flags)
{
_bytes_in_use += sizeof(*this);
}
// serialize _value into the buffer, but only if it is big enough.
@ -716,6 +730,7 @@ public:
Flags flags = k_flags_none) :
AP_Var(key, name, flags)
{
_bytes_in_use += sizeof(*this);
}
/// Constructor for a grouped array.
@ -735,6 +750,7 @@ public:
Flags flags = k_flags_none) :
AP_Var(group, index, name, flags)
{
_bytes_in_use += sizeof(*this);
}
// serialize _value into the buffer, but only if it is big enough.
@ -829,6 +845,7 @@ public:
Flags flags = k_flags_none) :
AP_Float(initial_value, key, name, flags)
{
_bytes_in_use += sizeof(*this);
}
AP_Float16(AP_Var_group *group,
@ -838,6 +855,7 @@ public:
Flags flags = k_flags_none) :
AP_Float(group, index, initial_value, name, flags)
{
_bytes_in_use += sizeof(*this);
}