mirror of https://github.com/ArduPilot/ardupilot
AP_Common: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
4bf2d87d70
commit
5620fee636
|
@ -40,7 +40,7 @@ bool MultiHeap::create(uint32_t total_size, uint8_t max_heaps)
|
|||
// don't allow double allocation
|
||||
return false;
|
||||
}
|
||||
heaps = new void*[max_heaps];
|
||||
heaps = NEW_NOTHROW void*[max_heaps];
|
||||
if (heaps == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -1,4 +1,5 @@
|
|||
#include <AP_gtest.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
int hal = 0;
|
||||
|
||||
|
@ -10,7 +11,7 @@ public:
|
|||
|
||||
TEST(AP_Common, TEST_CPP)
|
||||
{
|
||||
DummyDummy * test_new = new DummyDummy[1];
|
||||
DummyDummy * test_new = NEW_NOTHROW DummyDummy[1];
|
||||
EXPECT_FALSE(test_new == nullptr);
|
||||
EXPECT_TRUE(sizeof(test_new) == 8);
|
||||
EXPECT_FLOAT_EQ(test_new->count, 1);
|
||||
|
@ -22,7 +23,7 @@ TEST(AP_Common, TEST_CPP)
|
|||
EXPECT_EQ(test_d->count, 0); // constructor isn't called
|
||||
EXPECT_FLOAT_EQ(test_d->d, 0.0);
|
||||
|
||||
DummyDummy * test_d2 = new DummyDummy;
|
||||
DummyDummy * test_d2 = NEW_NOTHROW DummyDummy;
|
||||
EXPECT_TRUE(sizeof(test_d2) == 8);
|
||||
EXPECT_EQ(test_d2->count, 1);
|
||||
EXPECT_FLOAT_EQ(test_d2->d, 42.0);
|
||||
|
|
|
@ -6,7 +6,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
|
||||
TEST(ExpandingString, Tests)
|
||||
{
|
||||
ExpandingString *test_string = new ExpandingString();
|
||||
ExpandingString *test_string = NEW_NOTHROW ExpandingString();
|
||||
test_string->printf("Test\n");
|
||||
EXPECT_STREQ("Test\n", test_string->get_string());
|
||||
EXPECT_STREQ("Test\n", test_string->get_writeable_string());
|
||||
|
@ -15,7 +15,7 @@ TEST(ExpandingString, Tests)
|
|||
EXPECT_TRUE(test_string->append("Test2\n", 6));
|
||||
test_string->~ExpandingString();
|
||||
EXPECT_STRNE("Test\n", test_string->get_string());
|
||||
test_string = new ExpandingString();
|
||||
test_string = NEW_NOTHROW ExpandingString();
|
||||
char long_string[2048];
|
||||
std::fill(std::begin(long_string),std::end(long_string),'a');
|
||||
test_string->printf("%s", long_string);
|
||||
|
|
|
@ -70,21 +70,21 @@ void print_vprintf(AP_HAL::BetterStream *s, const char *fmt, va_list ap) {
|
|||
TEST(ExpandingString, Tests)
|
||||
{
|
||||
// Test print_vprintf failure.
|
||||
ExpandingString *test_string = new ExpandingString();
|
||||
ExpandingString *test_string = NEW_NOTHROW ExpandingString();
|
||||
test_string->printf("Test\n");
|
||||
EXPECT_STREQ("", test_string->get_string());
|
||||
EXPECT_STREQ("", test_string->get_writeable_string());
|
||||
EXPECT_EQ(0u, test_string->get_length());
|
||||
EXPECT_FALSE(test_string->has_failed_allocation());
|
||||
// test failure on second printf expand()
|
||||
test_string = new ExpandingString();
|
||||
test_string = NEW_NOTHROW ExpandingString();
|
||||
test_string->printf("Test\n");
|
||||
EXPECT_STREQ("", test_string->get_string());
|
||||
EXPECT_STREQ("", test_string->get_writeable_string());
|
||||
EXPECT_EQ(0u, test_string->get_length());
|
||||
EXPECT_TRUE(test_string->has_failed_allocation());
|
||||
// Test realloc failure
|
||||
test_string = new ExpandingString();
|
||||
test_string = NEW_NOTHROW ExpandingString();
|
||||
test_string->printf("Test\n");
|
||||
EXPECT_STREQ(nullptr, test_string->get_string());
|
||||
EXPECT_STREQ(nullptr, test_string->get_writeable_string());
|
||||
|
@ -99,7 +99,7 @@ TEST(ExpandingString, Tests)
|
|||
EXPECT_EQ(0u, test_string->get_length());
|
||||
EXPECT_TRUE(test_string->has_failed_allocation());
|
||||
// test failure on append realloc
|
||||
test_string = new ExpandingString();
|
||||
test_string = NEW_NOTHROW ExpandingString();
|
||||
EXPECT_FALSE(test_string->append("Test2\n", 6));
|
||||
EXPECT_TRUE(test_string->has_failed_allocation());
|
||||
EXPECT_STREQ(nullptr, test_string->get_string());
|
||||
|
|
Loading…
Reference in New Issue