mirror of https://github.com/ArduPilot/ardupilot
ap_common: use intptr_t for pointer casts
this allows building on systems with pointers that aren't 16 bits long
This commit is contained in:
parent
298cc51118
commit
88668dd2d1
|
@ -108,7 +108,7 @@ public:
|
||||||
/// @return An opaque handle
|
/// @return An opaque handle
|
||||||
///
|
///
|
||||||
Meta_handle meta_get_handle(void) const {
|
Meta_handle meta_get_handle(void) const {
|
||||||
return ((Meta_handle)meta_type_id() << 16) | (uint16_t)this;
|
return ((Meta_handle)meta_type_id() << 16) | (uintptr_t)this;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Validates an AP_Meta_class handle.
|
/// Validates an AP_Meta_class handle.
|
||||||
|
@ -134,7 +134,7 @@ 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 - 2)) { // -2 to account for the type_id
|
if ((uintptr_t)candidate >= (RAMEND - 2)) { // -2 to account for the type_id
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -78,10 +78,10 @@ int freeMemory()
|
||||||
{
|
{
|
||||||
int free_memory;
|
int free_memory;
|
||||||
|
|
||||||
if ((int)__brkval == 0)
|
if ((intptr_t)__brkval == 0)
|
||||||
free_memory = ((int)&free_memory) - ((int)&__bss_end);
|
free_memory = ((intptr_t)&free_memory) - ((intptr_t)&__bss_end);
|
||||||
else
|
else
|
||||||
free_memory = ((int)&free_memory) - ((int)__brkval);
|
free_memory = ((intptr_t)&free_memory) - ((intptr_t)__brkval);
|
||||||
|
|
||||||
return free_memory;
|
return free_memory;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue