mirror of https://github.com/ArduPilot/ardupilot
Metaclass improvements:
- Add a default ctor/dtor pair. The dtor ensures that all dtors are virtual, and guarantees that there is something in the dtor vtable slot for classes that don't implement their own. - serialize must not alter the class, mark it const - Improve documentation - Fix handle validation to prevent trying to read 2 bytes beyond the end of memory git-svn-id: https://arducopter.googlecode.com/svn/trunk@1416 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
ada5e7a75b
commit
158b3c91d3
|
@ -13,8 +13,20 @@
|
||||||
|
|
||||||
#include "AP_MetaClass.h"
|
#include "AP_MetaClass.h"
|
||||||
|
|
||||||
|
// Default ctor, currently does nothing
|
||||||
|
AP_MetaClass::AP_MetaClass(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
// Default dtor, currently does nothing but must be defined in order to ensure that
|
||||||
|
// subclasses not overloading the default virtual dtor still have something in their
|
||||||
|
// vtable.
|
||||||
|
AP_MetaClass::~AP_MetaClass()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
size_t
|
size_t
|
||||||
AP_MetaClass::serialize(void *buf, size_t bufSize)
|
AP_MetaClass::serialize(void *buf, size_t bufSize) const
|
||||||
{
|
{
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -26,6 +26,13 @@
|
||||||
class AP_MetaClass
|
class AP_MetaClass
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/// Default constructor does nothing.
|
||||||
|
AP_MetaClass(void);
|
||||||
|
|
||||||
|
/// Default destructor is virtual, to ensure that all destructors
|
||||||
|
/// are called for derived classes.
|
||||||
|
virtual ~AP_MetaClass();
|
||||||
|
|
||||||
/// Type code, unique to all instances of a given subclass.
|
/// Type code, unique to all instances of a given subclass.
|
||||||
typedef uint16_t AP_TypeID;
|
typedef uint16_t AP_TypeID;
|
||||||
|
|
||||||
|
@ -45,8 +52,10 @@ public:
|
||||||
return *(AP_TypeID *)this;
|
return *(AP_TypeID *)this;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// External handle, contains enough information to validate a pointer
|
/// External handle for an instance of an AP_MetaClass subclass, contains
|
||||||
|
/// enough information to construct and validate a pointer to the instance
|
||||||
/// when passed back from an untrusted source.
|
/// when passed back from an untrusted source.
|
||||||
|
///
|
||||||
typedef uint32_t AP_MetaHandle;
|
typedef uint32_t AP_MetaHandle;
|
||||||
|
|
||||||
/// Return a value that can be used as an external pointer to an instance
|
/// Return a value that can be used as an external pointer to an instance
|
||||||
|
@ -86,12 +95,15 @@ public:
|
||||||
// Note that this implies that we cannot deal with objects in ROM or EEPROM,
|
// Note that this implies that we cannot deal with objects in ROM or EEPROM,
|
||||||
// but the constructor wouldn't be able to populate a vtable pointer there anyway...
|
// but the constructor wouldn't be able to populate a vtable pointer there anyway...
|
||||||
//
|
//
|
||||||
if ((uint16_t)candidate >= RAMEND)
|
if ((uint16_t)candidate >= (RAMEND - 2)) // -2 to account for the type_id
|
||||||
return NULL;
|
return NULL;
|
||||||
|
|
||||||
// Compare the type of the object that candidate points to (or garbage if it doesn't)
|
// Compare the typeid of the object that candidate points to with the typeid
|
||||||
// with .
|
// from the handle. Note that it's safe to call meta_type_id() off the untrusted
|
||||||
if (candidate->meta_type_id() == id) // compare claimed type with object type
|
// candidate pointer because meta_type_id is non-virtual (and will in fact be
|
||||||
|
// inlined here).
|
||||||
|
//
|
||||||
|
if (candidate->meta_type_id() == id)
|
||||||
return candidate;
|
return candidate;
|
||||||
|
|
||||||
return NULL;
|
return NULL;
|
||||||
|
@ -114,8 +126,8 @@ public:
|
||||||
|
|
||||||
/// Cast an object to an expected class type.
|
/// Cast an object to an expected class type.
|
||||||
///
|
///
|
||||||
/// This should be used with caution, as _typename's default constructor will be run,
|
/// This should be used with caution, as _typename's default constructor and
|
||||||
/// possibly introducing undesired side-effects.
|
/// destructor will be run, possibly introducing undesired side-effects.
|
||||||
///
|
///
|
||||||
/// @todo Consider whether we should make it difficult to have a default constructor
|
/// @todo Consider whether we should make it difficult to have a default constructor
|
||||||
/// with appreciable side-effects.
|
/// with appreciable side-effects.
|
||||||
|
@ -148,7 +160,7 @@ public:
|
||||||
/// have overflowed the buffer. If the return value is zero,
|
/// have overflowed the buffer. If the return value is zero,
|
||||||
/// the class does not support serialisation.
|
/// the class does not support serialisation.
|
||||||
///
|
///
|
||||||
virtual size_t serialize(void *buf, size_t bufSize);
|
virtual size_t serialize(void *buf, size_t bufSize) const;
|
||||||
|
|
||||||
/// Unserialise the class.
|
/// Unserialise the class.
|
||||||
///
|
///
|
||||||
|
|
Loading…
Reference in New Issue