mirror of https://github.com/ArduPilot/ardupilot
AP_Common: added checks for new without std::nothrow
and add NEW_NOTHROW macro
This commit is contained in:
parent
4f6653e5c7
commit
aa2f885e2f
|
@ -23,6 +23,7 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <type_traits>
|
#include <type_traits>
|
||||||
|
#include <new>
|
||||||
|
|
||||||
// used to pack structures
|
// used to pack structures
|
||||||
#define PACKED __attribute__((__packed__))
|
#define PACKED __attribute__((__packed__))
|
||||||
|
@ -184,3 +185,10 @@ template <typename T> void BIT_CLEAR (T& value, uint8_t bitnumber) noexcept {
|
||||||
((value) &= ~((T)(1U) << (bitnumber)));
|
((value) &= ~((T)(1U) << (bitnumber)));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
See the comments in libraries/AP_Common/c++.cpp
|
||||||
|
*/
|
||||||
|
#ifndef NEW_NOTHROW
|
||||||
|
#define NEW_NOTHROW new(std::nothrow)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -16,6 +16,8 @@
|
||||||
#include "AP_ExpandingArray.h"
|
#include "AP_ExpandingArray.h"
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
#ifndef HAL_BOOTLOADER_BUILD
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
AP_ExpandingArrayGeneric::~AP_ExpandingArrayGeneric(void)
|
AP_ExpandingArrayGeneric::~AP_ExpandingArrayGeneric(void)
|
||||||
|
@ -75,3 +77,5 @@ bool AP_ExpandingArrayGeneric::expand_to_hold(uint16_t num_items)
|
||||||
uint16_t chunks_required = ((num_items - max_items()) / chunk_size) + 1;
|
uint16_t chunks_required = ((num_items - max_items()) / chunk_size) + 1;
|
||||||
return expand(chunks_required);
|
return expand(chunks_required);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAL_BOOTLOADER_BUILD
|
||||||
|
|
|
@ -17,9 +17,10 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "ExpandingString.h"
|
#include "ExpandingString.h"
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
#ifndef HAL_BOOTLOADER_BUILD
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define EXPAND_INCREMENT 512
|
#define EXPAND_INCREMENT 512
|
||||||
|
@ -127,3 +128,5 @@ void ExpandingString::set_buffer(char *s, uint32_t total_len, uint32_t used_len)
|
||||||
allocation_failed = false;
|
allocation_failed = false;
|
||||||
external_buffer = true;
|
external_buffer = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAL_BOOTLOADER_BUILD
|
||||||
|
|
|
@ -4,6 +4,8 @@
|
||||||
|
|
||||||
#include "Location.h"
|
#include "Location.h"
|
||||||
|
|
||||||
|
#ifndef HAL_BOOTLOADER_BUILD
|
||||||
|
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
|
|
||||||
|
@ -527,3 +529,5 @@ void Location::linearly_interpolate_alt(const Location &point1, const Location &
|
||||||
// new target's distance along the original track and then linear interpolate between the original origin and destination altitudes
|
// new target's distance along the original track and then linear interpolate between the original origin and destination altitudes
|
||||||
set_alt_cm(point1.alt + (point2.alt - point1.alt) * constrain_float(line_path_proportion(point1, point2), 0.0f, 1.0f), point2.get_alt_frame());
|
set_alt_cm(point1.alt + (point2.alt - point1.alt) * constrain_float(line_path_proportion(point1, point2), 0.0f, 1.0f), point2.get_alt_frame());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAL_BOOTLOADER_BUILD
|
||||||
|
|
|
@ -10,6 +10,8 @@
|
||||||
|
|
||||||
#include "MultiHeap.h"
|
#include "MultiHeap.h"
|
||||||
|
|
||||||
|
#ifndef HAL_BOOTLOADER_BUILD
|
||||||
|
|
||||||
/*
|
/*
|
||||||
on ChibiOS allow up to 4 heaps. On other HALs only allow a single
|
on ChibiOS allow up to 4 heaps. On other HALs only allow a single
|
||||||
heap. This is needed as hal.util->heap_realloc() needs to have the
|
heap. This is needed as hal.util->heap_realloc() needs to have the
|
||||||
|
@ -141,3 +143,6 @@ void *MultiHeap::change_size(void *ptr, uint32_t old_size, uint32_t new_size)
|
||||||
*/
|
*/
|
||||||
return hal.util->heap_realloc(heaps[0], ptr, old_size, new_size);
|
return hal.util->heap_realloc(heaps[0], ptr, old_size, new_size);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAL_BOOTLOADER_BUILD
|
||||||
|
|
||||||
|
|
|
@ -1,15 +1,61 @@
|
||||||
//
|
/*
|
||||||
// C++ runtime support not provided by Arduino
|
wrapper around new for C++ to ensure we always get zero filled memory
|
||||||
//
|
*/
|
||||||
// Note: use new/delete with caution. The heap is small and
|
|
||||||
// easily fragmented.
|
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
#include <new>
|
||||||
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
|
|
||||||
/*
|
/*
|
||||||
globally override new and delete to ensure that we always start with
|
globally override new and delete to ensure that we always start with
|
||||||
zero memory. This ensures consistent behaviour.
|
zero memory. This ensures consistent behaviour.
|
||||||
|
|
||||||
|
Note that new comes in multiple different variants. When new is used
|
||||||
|
without std::nothrow the compiler is free to assume it will not fail
|
||||||
|
as it assumes exceptions are enabled. This makes code like this
|
||||||
|
unsafe when using -fno-exceptions:
|
||||||
|
|
||||||
|
a = new b;
|
||||||
|
if (a == nullptr) {
|
||||||
|
handle_error()
|
||||||
|
}
|
||||||
|
|
||||||
|
the compiler may remove the error handling. With g++ you can use
|
||||||
|
-fcheck-new to avoid this, but on clang++ the compiler accepts
|
||||||
|
-fcheck-new as a valid flag, but doesn't implement it, and may elide
|
||||||
|
the error checking. That makes using clang++ unsafe with
|
||||||
|
-fno-exceptions if you ever call new without std::nothrow.
|
||||||
|
|
||||||
|
To avoid this we define NEW_NOTHROW as new(std::nothrow) and use it
|
||||||
|
everywhere in ArduPilot, then we catch any missing cases with both
|
||||||
|
an internal error and with a check of the elf for the symbols we
|
||||||
|
want to avoid
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
variant for new(std::nothrow), which is all that should be used in
|
||||||
|
ArduPilot
|
||||||
|
*/
|
||||||
|
void * operator new(size_t size, std::nothrow_t const ¬hrow)
|
||||||
|
{
|
||||||
|
if (size < 1) {
|
||||||
|
size = 1;
|
||||||
|
}
|
||||||
|
return(calloc(size, 1));
|
||||||
|
}
|
||||||
|
|
||||||
|
void * operator new[](size_t size, std::nothrow_t const ¬hrow)
|
||||||
|
{
|
||||||
|
if (size < 1) {
|
||||||
|
size = 1;
|
||||||
|
}
|
||||||
|
return(calloc(size, 1));
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
These variants are for new without std::nothrow. We don't want to ever
|
||||||
|
use this from ArduPilot code
|
||||||
*/
|
*/
|
||||||
void * operator new(size_t size)
|
void * operator new(size_t size)
|
||||||
{
|
{
|
||||||
|
@ -19,20 +65,41 @@ void * operator new(size_t size)
|
||||||
return(calloc(size, 1));
|
return(calloc(size, 1));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void * operator new[](size_t size)
|
||||||
|
{
|
||||||
|
if (size < 1) {
|
||||||
|
size = 1;
|
||||||
|
}
|
||||||
|
return(calloc(size, 1));
|
||||||
|
}
|
||||||
|
|
||||||
void operator delete(void *p)
|
void operator delete(void *p)
|
||||||
{
|
{
|
||||||
if (p) free(p);
|
if (p) free(p);
|
||||||
}
|
}
|
||||||
|
|
||||||
void * operator new[](size_t size)
|
|
||||||
{
|
|
||||||
if (size < 1) {
|
|
||||||
size = 1;
|
|
||||||
}
|
|
||||||
return(calloc(size, 1));
|
|
||||||
}
|
|
||||||
|
|
||||||
void operator delete[](void * ptr)
|
void operator delete[](void * ptr)
|
||||||
{
|
{
|
||||||
if (ptr) free(ptr);
|
if (ptr) free(ptr);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS
|
||||||
|
/*
|
||||||
|
wrapper around malloc to ensure all memory is initialised as zero
|
||||||
|
ChibiOS has its own wrapper
|
||||||
|
*/
|
||||||
|
extern "C" {
|
||||||
|
void *__wrap_malloc(size_t size);
|
||||||
|
void *__real_malloc(size_t size);
|
||||||
|
}
|
||||||
|
void *__wrap_malloc(size_t size)
|
||||||
|
{
|
||||||
|
void *ret = __real_malloc(size);
|
||||||
|
if (ret != nullptr) {
|
||||||
|
memset(ret, 0, size);
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue