mirror of https://github.com/ArduPilot/ardupilot
Tools: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
5113b6af59
commit
94841dd608
|
@ -342,7 +342,7 @@ bool flash_from_sd()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
verifier = new ABinVerifier{verify_abin_path};
|
verifier = NEW_NOTHROW ABinVerifier{verify_abin_path};
|
||||||
if (!verifier->run()) {
|
if (!verifier->run()) {
|
||||||
goto out;
|
goto out;
|
||||||
}
|
}
|
||||||
|
@ -354,7 +354,7 @@ bool flash_from_sd()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
flasher = new ABinFlasher{flash_abin_path};
|
flasher = NEW_NOTHROW ABinFlasher{flash_abin_path};
|
||||||
if (!flasher->run()) {
|
if (!flasher->run()) {
|
||||||
goto out;
|
goto out;
|
||||||
}
|
}
|
||||||
|
|
|
@ -554,7 +554,7 @@ void BL_Network::net_request_trampoline(void *ctx)
|
||||||
*/
|
*/
|
||||||
void BL_Network::web_server(void)
|
void BL_Network::web_server(void)
|
||||||
{
|
{
|
||||||
auto *listen_socket = new SocketAPM(0);
|
auto *listen_socket = NEW_NOTHROW SocketAPM(0);
|
||||||
listen_socket->bind("0.0.0.0", 80);
|
listen_socket->bind("0.0.0.0", 80);
|
||||||
listen_socket->listen(20);
|
listen_socket->listen(20);
|
||||||
|
|
||||||
|
@ -573,7 +573,7 @@ void BL_Network::web_server(void)
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
// a new thread for each connection to allow for AJAX
|
// a new thread for each connection to allow for AJAX
|
||||||
auto *req = new req_context;
|
auto *req = NEW_NOTHROW req_context;
|
||||||
req->driver = this;
|
req->driver = this;
|
||||||
req->sock = sock;
|
req->sock = sock;
|
||||||
thread_create_alloc(THD_WORKING_AREA_SIZE(2048),
|
thread_create_alloc(THD_WORKING_AREA_SIZE(2048),
|
||||||
|
@ -601,7 +601,7 @@ void BL_Network::init()
|
||||||
|
|
||||||
macInit();
|
macInit();
|
||||||
|
|
||||||
thisif = new netif;
|
thisif = NEW_NOTHROW netif;
|
||||||
|
|
||||||
net_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(2048),
|
net_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(2048),
|
||||||
"network",
|
"network",
|
||||||
|
|
|
@ -268,7 +268,7 @@ void AP_Periph_FW::init()
|
||||||
for (uint8_t i = 0; i < ESC_NUMBERS; i++) {
|
for (uint8_t i = 0; i < ESC_NUMBERS; i++) {
|
||||||
const uint8_t port = g.esc_serial_port[i];
|
const uint8_t port = g.esc_serial_port[i];
|
||||||
if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports
|
if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports
|
||||||
apd_esc_telem[i] = new ESC_APD_Telem (hal.serial(port), g.pole_count[i]);
|
apd_esc_telem[i] = NEW_NOTHROW ESC_APD_Telem (hal.serial(port), g.pole_count[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -61,7 +61,7 @@ protected:
|
||||||
|
|
||||||
GCS_MAVLINK_Periph *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
GCS_MAVLINK_Periph *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
||||||
AP_HAL::UARTDriver &uart) override {
|
AP_HAL::UARTDriver &uart) override {
|
||||||
return new GCS_MAVLINK_Periph(params, uart);
|
return NEW_NOTHROW GCS_MAVLINK_Periph(params, uart);
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -80,7 +80,7 @@ void AP_Periph_FW::batt_balance_update()
|
||||||
|
|
||||||
// allocate cell sources if needed
|
// allocate cell sources if needed
|
||||||
if (battery_balance.cells == nullptr) {
|
if (battery_balance.cells == nullptr) {
|
||||||
battery_balance.cells = new AP_HAL::AnalogSource*[ncell];
|
battery_balance.cells = NEW_NOTHROW AP_HAL::AnalogSource*[ncell];
|
||||||
if (battery_balance.cells == nullptr) {
|
if (battery_balance.cells == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -98,8 +98,8 @@ void AP_Periph_FW::batt_balance_update()
|
||||||
|
|
||||||
// allocate space for the packet. This is a large
|
// allocate space for the packet. This is a large
|
||||||
// packet that won't fit on the stack, so dynamically allocate
|
// packet that won't fit on the stack, so dynamically allocate
|
||||||
auto *pkt = new ardupilot_equipment_power_BatteryInfoAux;
|
auto *pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux;
|
||||||
uint8_t *buffer = new uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];
|
uint8_t *buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];
|
||||||
if (pkt == nullptr || buffer == nullptr) {
|
if (pkt == nullptr || buffer == nullptr) {
|
||||||
delete pkt;
|
delete pkt;
|
||||||
delete [] buffer;
|
delete [] buffer;
|
||||||
|
|
|
@ -90,8 +90,8 @@ void AP_Periph_FW::can_battery_send_cells(uint8_t instance)
|
||||||
{
|
{
|
||||||
// allocate space for the packet. This is a large
|
// allocate space for the packet. This is a large
|
||||||
// packet that won't fit on the stack, so dynamically allocate
|
// packet that won't fit on the stack, so dynamically allocate
|
||||||
auto* pkt = new ardupilot_equipment_power_BatteryInfoAux;
|
auto* pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux;
|
||||||
uint8_t* buffer = new uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];
|
uint8_t* buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];
|
||||||
if (pkt == nullptr || buffer == nullptr) {
|
if (pkt == nullptr || buffer == nullptr) {
|
||||||
delete pkt;
|
delete pkt;
|
||||||
delete [] buffer;
|
delete [] buffer;
|
||||||
|
|
|
@ -1622,15 +1622,15 @@ void AP_Periph_FW::can_start()
|
||||||
|
|
||||||
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
|
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
can_iface_periph[i] = new ChibiOS::CANIface();
|
can_iface_periph[i] = NEW_NOTHROW ChibiOS::CANIface();
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
can_iface_periph[i] = new HALSITL::CANIface();
|
can_iface_periph[i] = NEW_NOTHROW HALSITL::CANIface();
|
||||||
#endif
|
#endif
|
||||||
instances[i].iface = can_iface_periph[i];
|
instances[i].iface = can_iface_periph[i];
|
||||||
instances[i].index = i;
|
instances[i].index = i;
|
||||||
#if HAL_PERIPH_CAN_MIRROR
|
#if HAL_PERIPH_CAN_MIRROR
|
||||||
if ((g.can_mirror_ports & (1U << i)) != 0) {
|
if ((g.can_mirror_ports & (1U << i)) != 0) {
|
||||||
instances[i].mirror_queue = new ObjectBuffer<AP_HAL::CANFrame> (HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE);
|
instances[i].mirror_queue = NEW_NOTHROW ObjectBuffer<AP_HAL::CANFrame> (HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE);
|
||||||
}
|
}
|
||||||
#endif //HAL_PERIPH_CAN_MIRROR
|
#endif //HAL_PERIPH_CAN_MIRROR
|
||||||
#if HAL_NUM_CAN_IFACES >= 2
|
#if HAL_NUM_CAN_IFACES >= 2
|
||||||
|
|
|
@ -79,7 +79,7 @@ void AP_Periph_FW::handle_tunnel_Targetted(CanardInstance* canard_ins, CanardRxT
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (uart_monitor.buffer == nullptr) {
|
if (uart_monitor.buffer == nullptr) {
|
||||||
uart_monitor.buffer = new ByteBuffer(1024);
|
uart_monitor.buffer = NEW_NOTHROW ByteBuffer(1024);
|
||||||
if (uart_monitor.buffer == nullptr) {
|
if (uart_monitor.buffer == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -61,71 +61,71 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
||||||
|
|
||||||
// map from format name to a parser subclass:
|
// map from format name to a parser subclass:
|
||||||
if (streq(name, "PARM")) {
|
if (streq(name, "PARM")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_PARM(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_PARM(formats[f.type]);
|
||||||
} else if (streq(name, "RFRH")) {
|
} else if (streq(name, "RFRH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RFRH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RFRH(formats[f.type]);
|
||||||
} else if (streq(name, "RFRF")) {
|
} else if (streq(name, "RFRF")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RFRF(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RFRF(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RFRN")) {
|
} else if (streq(name, "RFRN")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RFRN(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RFRN(formats[f.type]);
|
||||||
} else if (streq(name, "REV2")) {
|
} else if (streq(name, "REV2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_REV2(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REV2(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RSO2")) {
|
} else if (streq(name, "RSO2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RSO2(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RSO2(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RWA2")) {
|
} else if (streq(name, "RWA2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RWA2(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RWA2(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "REV3")) {
|
} else if (streq(name, "REV3")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_REV3(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REV3(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RSO3")) {
|
} else if (streq(name, "RSO3")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RSO3(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RSO3(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RWA3")) {
|
} else if (streq(name, "RWA3")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RWA3(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RWA3(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "REY3")) {
|
} else if (streq(name, "REY3")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_REY3(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REY3(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RISH")) {
|
} else if (streq(name, "RISH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RISH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RISH(formats[f.type]);
|
||||||
} else if (streq(name, "RISI")) {
|
} else if (streq(name, "RISI")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RISI(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RISI(formats[f.type]);
|
||||||
} else if (streq(name, "RASH")) {
|
} else if (streq(name, "RASH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RASH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RASH(formats[f.type]);
|
||||||
} else if (streq(name, "RASI")) {
|
} else if (streq(name, "RASI")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RASI(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RASI(formats[f.type]);
|
||||||
} else if (streq(name, "RBRH")) {
|
} else if (streq(name, "RBRH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RBRH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBRH(formats[f.type]);
|
||||||
} else if (streq(name, "RBRI")) {
|
} else if (streq(name, "RBRI")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RBRI(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBRI(formats[f.type]);
|
||||||
} else if (streq(name, "RRNH")) {
|
} else if (streq(name, "RRNH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RRNH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RRNH(formats[f.type]);
|
||||||
} else if (streq(name, "RRNI")) {
|
} else if (streq(name, "RRNI")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RRNI(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RRNI(formats[f.type]);
|
||||||
} else if (streq(name, "RGPH")) {
|
} else if (streq(name, "RGPH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RGPH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RGPH(formats[f.type]);
|
||||||
} else if (streq(name, "RGPI")) {
|
} else if (streq(name, "RGPI")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RGPI(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RGPI(formats[f.type]);
|
||||||
} else if (streq(name, "RGPJ")) {
|
} else if (streq(name, "RGPJ")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RGPJ(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RGPJ(formats[f.type]);
|
||||||
} else if (streq(name, "RMGH")) {
|
} else if (streq(name, "RMGH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RMGH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RMGH(formats[f.type]);
|
||||||
} else if (streq(name, "RMGI")) {
|
} else if (streq(name, "RMGI")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RMGI(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RMGI(formats[f.type]);
|
||||||
} else if (streq(name, "RBCH")) {
|
} else if (streq(name, "RBCH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RBCH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBCH(formats[f.type]);
|
||||||
} else if (streq(name, "RBCI")) {
|
} else if (streq(name, "RBCI")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RBCI(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBCI(formats[f.type]);
|
||||||
} else if (streq(name, "RVOH")) {
|
} else if (streq(name, "RVOH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RVOH(formats[f.type]);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RVOH(formats[f.type]);
|
||||||
} else if (streq(name, "ROFH")) {
|
} else if (streq(name, "ROFH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_ROFH(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_ROFH(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "REPH")) {
|
} else if (streq(name, "REPH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_REPH(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REPH(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RSLL")) {
|
} else if (streq(name, "RSLL")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RSLL(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RSLL(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "REVH")) {
|
} else if (streq(name, "REVH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_REVH(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REVH(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RWOH")) {
|
} else if (streq(name, "RWOH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RWOH(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RWOH(formats[f.type], ekf2, ekf3);
|
||||||
} else if (streq(name, "RBOH")) {
|
} else if (streq(name, "RBOH")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_RBOH(formats[f.type], ekf2, ekf3);
|
msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBOH(formats[f.type], ekf2, ekf3);
|
||||||
} else {
|
} else {
|
||||||
// debug(" No parser for (%s)\n", name);
|
// debug(" No parser for (%s)\n", name);
|
||||||
}
|
}
|
||||||
|
|
|
@ -161,7 +161,7 @@ void Replay::_parse_command_line(uint8_t argc, char * const argv[])
|
||||||
::printf("Usage: -p NAME=VALUE\n");
|
::printf("Usage: -p NAME=VALUE\n");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
struct user_parameter *u = new user_parameter;
|
struct user_parameter *u = NEW_NOTHROW user_parameter;
|
||||||
strncpy(u->name, gopt.optarg, eq-gopt.optarg);
|
strncpy(u->name, gopt.optarg, eq-gopt.optarg);
|
||||||
u->value = atof(eq+1);
|
u->value = atof(eq+1);
|
||||||
u->next = user_parameters;
|
u->next = user_parameters;
|
||||||
|
@ -310,7 +310,7 @@ void Replay::load_param_file(const char *pfilename)
|
||||||
if (!parse_param_line(line, &pname, value)) {
|
if (!parse_param_line(line, &pname, value)) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
struct user_parameter *u = new user_parameter;
|
struct user_parameter *u = NEW_NOTHROW user_parameter;
|
||||||
strncpy_noterm(u->name, pname, sizeof(u->name));
|
strncpy_noterm(u->name, pname, sizeof(u->name));
|
||||||
u->value = value;
|
u->value = value;
|
||||||
u->next = user_parameters;
|
u->next = user_parameters;
|
||||||
|
|
Loading…
Reference in New Issue