mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
5af89a4291
commit
a2459c6e61
|
@ -259,7 +259,7 @@ void AP_Scripting::thread(void) {
|
|||
_restart = false;
|
||||
_init_failed = false;
|
||||
|
||||
lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_options);
|
||||
lua_scripts *lua = NEW_NOTHROW lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_options);
|
||||
if (lua == nullptr || !lua->heap_allocated()) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "Unable to allocate memory");
|
||||
_init_failed = true;
|
||||
|
@ -340,7 +340,7 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd
|
|||
|
||||
if (mission_data == nullptr) {
|
||||
// load buffer
|
||||
mission_data = new ObjectBuffer<struct AP_Scripting::scripting_mission_cmd>(mission_cmd_queue_size);
|
||||
mission_data = NEW_NOTHROW ObjectBuffer<struct AP_Scripting::scripting_mission_cmd>(mission_cmd_queue_size);
|
||||
if (mission_data != nullptr && mission_data->get_size() == 0) {
|
||||
delete mission_data;
|
||||
mission_data = nullptr;
|
||||
|
|
|
@ -39,7 +39,7 @@ void ScriptingCANSensor::handle_frame(AP_HAL::CANFrame &frame)
|
|||
ScriptingCANBuffer* ScriptingCANSensor::add_buffer(uint32_t buffer_len)
|
||||
{
|
||||
WITH_SEMAPHORE(sem);
|
||||
ScriptingCANBuffer *new_buff = new ScriptingCANBuffer(*this, buffer_len);
|
||||
ScriptingCANBuffer *new_buff = NEW_NOTHROW ScriptingCANBuffer(*this, buffer_len);
|
||||
if (buffer_list == nullptr) {
|
||||
buffer_list = new_buff;
|
||||
} else {
|
||||
|
|
|
@ -54,16 +54,16 @@ bool Parameter::init_by_info(uint16_t key, uint32_t group_element, enum ap_var_t
|
|||
{
|
||||
switch (type) {
|
||||
case AP_PARAM_INT8:
|
||||
vp = new AP_Int8;
|
||||
vp = NEW_NOTHROW AP_Int8;
|
||||
break;
|
||||
case AP_PARAM_INT16:
|
||||
vp = new AP_Int16;
|
||||
vp = NEW_NOTHROW AP_Int16;
|
||||
break;
|
||||
case AP_PARAM_INT32:
|
||||
vp = new AP_Int32;
|
||||
vp = NEW_NOTHROW AP_Int32;
|
||||
break;
|
||||
case AP_PARAM_FLOAT:
|
||||
vp = new AP_Float;
|
||||
vp = NEW_NOTHROW AP_Float;
|
||||
break;
|
||||
default:
|
||||
return false;
|
||||
|
|
|
@ -64,13 +64,13 @@ int lua_mavlink_init(lua_State *L) {
|
|||
|
||||
struct AP_Scripting::mavlink &data = AP::scripting()->mavlink_data;
|
||||
if (data.rx_buffer == nullptr) {
|
||||
data.rx_buffer = new ObjectBuffer<struct AP_Scripting::mavlink_msg>(queue_size);
|
||||
data.rx_buffer = NEW_NOTHROW ObjectBuffer<struct AP_Scripting::mavlink_msg>(queue_size);
|
||||
if (data.rx_buffer == nullptr) {
|
||||
return luaL_error(L, "Failed to allocate mavlink rx buffer");
|
||||
}
|
||||
}
|
||||
if (data.accept_msg_ids == nullptr) {
|
||||
data.accept_msg_ids = new uint32_t[num_msgs];
|
||||
data.accept_msg_ids = NEW_NOTHROW uint32_t[num_msgs];
|
||||
if (data.accept_msg_ids == nullptr) {
|
||||
return luaL_error(L, "Failed to allocate mavlink rx registry");
|
||||
}
|
||||
|
@ -203,7 +203,7 @@ int lua_mavlink_block_command(lua_State *L) {
|
|||
}
|
||||
|
||||
// Add new list item
|
||||
AP_Scripting::command_block_list *new_item = new AP_Scripting::command_block_list;
|
||||
AP_Scripting::command_block_list *new_item = NEW_NOTHROW AP_Scripting::command_block_list;
|
||||
if (new_item == nullptr) {
|
||||
lua_pushboolean(L, false);
|
||||
return 1;
|
||||
|
@ -577,7 +577,7 @@ int lua_get_i2c_device(lua_State *L) {
|
|||
return luaL_argerror(L, 1, "no i2c devices available");
|
||||
}
|
||||
|
||||
scripting->_i2c_dev[scripting->num_i2c_devices] = new AP_HAL::OwnPtr<AP_HAL::I2CDevice>;
|
||||
scripting->_i2c_dev[scripting->num_i2c_devices] = NEW_NOTHROW AP_HAL::OwnPtr<AP_HAL::I2CDevice>;
|
||||
if (scripting->_i2c_dev[scripting->num_i2c_devices] == nullptr) {
|
||||
return luaL_argerror(L, 1, "i2c device nullptr");
|
||||
}
|
||||
|
@ -676,7 +676,7 @@ int lua_get_CAN_device(lua_State *L) {
|
|||
auto *scripting = AP::scripting();
|
||||
|
||||
if (scripting->_CAN_dev == nullptr) {
|
||||
scripting->_CAN_dev = new ScriptingCANSensor(AP_CAN::Protocol::Scripting);
|
||||
scripting->_CAN_dev = NEW_NOTHROW ScriptingCANSensor(AP_CAN::Protocol::Scripting);
|
||||
if (scripting->_CAN_dev == nullptr) {
|
||||
return luaL_argerror(L, 1, "CAN device nullptr");
|
||||
}
|
||||
|
@ -707,7 +707,7 @@ int lua_get_CAN_device2(lua_State *L) {
|
|||
auto *scripting = AP::scripting();
|
||||
|
||||
if (scripting->_CAN_dev2 == nullptr) {
|
||||
scripting->_CAN_dev2 = new ScriptingCANSensor(AP_CAN::Protocol::Scripting2);
|
||||
scripting->_CAN_dev2 = NEW_NOTHROW ScriptingCANSensor(AP_CAN::Protocol::Scripting2);
|
||||
if (scripting->_CAN_dev2 == nullptr) {
|
||||
return luaL_argerror(L, 1, "CAN device nullptr");
|
||||
}
|
||||
|
@ -784,7 +784,7 @@ int lua_get_PWMSource(lua_State *L) {
|
|||
return luaL_argerror(L, 1, "no PWMSources available");
|
||||
}
|
||||
|
||||
scripting->_pwm_source[scripting->num_pwm_source] = new AP_HAL::PWMSource;
|
||||
scripting->_pwm_source[scripting->num_pwm_source] = NEW_NOTHROW AP_HAL::PWMSource;
|
||||
if (scripting->_pwm_source[scripting->num_pwm_source] == nullptr) {
|
||||
return luaL_argerror(L, 1, "PWMSources device nullptr");
|
||||
}
|
||||
|
@ -806,7 +806,7 @@ int lua_get_SocketAPM(lua_State *L) {
|
|||
const uint8_t datagram = get_uint8_t(L, 1);
|
||||
auto *scripting = AP::scripting();
|
||||
|
||||
auto *sock = new SocketAPM(datagram);
|
||||
auto *sock = NEW_NOTHROW SocketAPM(datagram);
|
||||
if (sock == nullptr) {
|
||||
return luaL_argerror(L, 1, "SocketAPM device nullptr");
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue