SITL: use NEW_NOTHROW for new(std::nothrow)

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:16 +10:00
parent 9b046f5a12
commit 4e1b2b95d4
43 changed files with 58 additions and 58 deletions

View File

@ -44,7 +44,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new AirSim(frame_str);
return NEW_NOTHROW AirSim(frame_str);
}
/* Create and set in/out socket for Airsim simulator */

View File

@ -31,7 +31,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new BalanceBot(frame_str);
return NEW_NOTHROW BalanceBot(frame_str);
}
private:

View File

@ -34,7 +34,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Balloon(frame_str);
return NEW_NOTHROW Balloon(frame_str);
}
private:

View File

@ -51,7 +51,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Blimp(frame_str);
return NEW_NOTHROW Blimp(frame_str);
}
protected:

View File

@ -44,7 +44,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new CRRCSim(frame_str);
return NEW_NOTHROW CRRCSim(frame_str);
}
private:

View File

@ -69,7 +69,7 @@ public:
void update(const struct sitl_input &input) override;
static Aircraft *create(const char *frame_str) {
return new Calibration(frame_str);
return NEW_NOTHROW Calibration(frame_str);
}
private:

View File

@ -592,7 +592,7 @@ void FlightAxis::socket_creator(void)
pthread_cond_wait(&sockcond2, &sockmtx);
}
pthread_mutex_unlock(&sockmtx);
auto *sck = new SocketAPM_native(false);
auto *sck = NEW_NOTHROW SocketAPM_native(false);
if (sck == nullptr) {
usleep(500);
continue;

View File

@ -44,7 +44,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new FlightAxis(frame_str);
return NEW_NOTHROW FlightAxis(frame_str);
}
struct state {

View File

@ -234,49 +234,49 @@ void GPS::check_backend_allocation()
#if AP_SIM_GPS_UBLOX_ENABLED
case Type::UBLOX:
backend = new GPS_UBlox(*this, instance);
backend = NEW_NOTHROW GPS_UBlox(*this, instance);
break;
#endif
#if AP_SIM_GPS_NMEA_ENABLED
case Type::NMEA:
backend = new GPS_NMEA(*this, instance);
backend = NEW_NOTHROW GPS_NMEA(*this, instance);
break;
#endif
#if AP_SIM_GPS_SBP_ENABLED
case Type::SBP:
backend = new GPS_SBP(*this, instance);
backend = NEW_NOTHROW GPS_SBP(*this, instance);
break;
#endif
#if AP_SIM_GPS_SBP2_ENABLED
case Type::SBP2:
backend = new GPS_SBP2(*this, instance);
backend = NEW_NOTHROW GPS_SBP2(*this, instance);
break;
#endif
#if AP_SIM_GPS_NOVA_ENABLED
case Type::NOVA:
backend = new GPS_NOVA(*this, instance);
backend = NEW_NOTHROW GPS_NOVA(*this, instance);
break;
#endif
#if AP_SIM_GPS_MSP_ENABLED
case Type::MSP:
backend = new GPS_MSP(*this, instance);
backend = NEW_NOTHROW GPS_MSP(*this, instance);
break;
#endif
#if AP_SIM_GPS_TRIMBLE_ENABLED
case Type::TRIMBLE:
backend = new GPS_Trimble(*this, instance);
backend = NEW_NOTHROW GPS_Trimble(*this, instance);
break;
#endif
#if AP_SIM_GPS_FILE_ENABLED
case Type::FILE:
backend = new GPS_FILE(*this, instance);
backend = NEW_NOTHROW GPS_FILE(*this, instance);
break;
#endif
};

View File

@ -50,7 +50,7 @@ void GPS_FILE::publish(const GPS_Data *d)
::lseek(fd[instance], -sizeof(header), SEEK_CUR);
return;
}
buf = new uint8_t[header.n];
buf = NEW_NOTHROW uint8_t[header.n];
if (buf != nullptr && ::read(fd[instance], buf, header.n) == ssize_t(header.n)) {
write_to_autopilot((const char *)buf, header.n);
delete[] buf;

View File

@ -43,7 +43,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Gazebo(frame_str);
return NEW_NOTHROW Gazebo(frame_str);
}
/* Create and set in/out socket for Gazebo simulator */

View File

@ -39,7 +39,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Glider(frame_str);
return NEW_NOTHROW Glider(frame_str);
}
bool on_ground() const override;

View File

@ -104,7 +104,7 @@ void Helicopter::update(const struct sitl_input &input)
}
} else if (servos_stored_buffer == nullptr) {
uint16_t buffer_size = constrain_int16(_time_delay, 1, 100) * 0.001f / dt;
servos_stored_buffer = new ObjectBuffer<servos_stored>(buffer_size);
servos_stored_buffer = NEW_NOTHROW ObjectBuffer<servos_stored>(buffer_size);
while (servos_stored_buffer->space() != 0) {
push_to_buffer(input.servos);
}

View File

@ -34,7 +34,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Helicopter(frame_str);
return NEW_NOTHROW Helicopter(frame_str);
}
protected:

View File

@ -44,7 +44,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new JSBSim(frame_str);
return NEW_NOTHROW JSBSim(frame_str);
}
private:

View File

@ -36,7 +36,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new JSON(frame_str);
return NEW_NOTHROW JSON(frame_str);
}
/* Create and set in/out socket for JSON generic simulator */

View File

@ -49,7 +49,7 @@ void JSON_Master::init(const int32_t num_slaves)
}
printf("Slave %u: listening on %u\n", list->instance, port);
list->next = new socket_list;
list->next = NEW_NOTHROW socket_list;
list = list->next;
initialized = true;

View File

@ -70,7 +70,7 @@ void LM2755::init()
// create objects for each of the channels to handle the dynamics
// of updating each. The channel gets references to the relevant
// configuration bytes.
d1 = new LEDChannel(
d1 = NEW_NOTHROW LEDChannel(
byte[(uint8_t)LM2755DevReg::D1_HIGH_LEVEL],
byte[(uint8_t)LM2755DevReg::D1_LOW_LEVEL],
byte[(uint8_t)LM2755DevReg::D1_DELAY],
@ -79,7 +79,7 @@ void LM2755::init()
byte[(uint8_t)LM2755DevReg::D1_RAMP_DOWN_STEP_TIME],
byte[(uint8_t)LM2755DevReg::D1_TIMING]
);
d2 = new LEDChannel(
d2 = NEW_NOTHROW LEDChannel(
byte[(uint8_t)LM2755DevReg::D2_HIGH_LEVEL],
byte[(uint8_t)LM2755DevReg::D2_LOW_LEVEL],
byte[(uint8_t)LM2755DevReg::D2_DELAY],
@ -88,7 +88,7 @@ void LM2755::init()
byte[(uint8_t)LM2755DevReg::D2_RAMP_DOWN_STEP_TIME],
byte[(uint8_t)LM2755DevReg::D2_TIMING]
);
d3 = new LEDChannel(
d3 = NEW_NOTHROW LEDChannel(
byte[(uint8_t)LM2755DevReg::D3_HIGH_LEVEL],
byte[(uint8_t)LM2755DevReg::D3_LOW_LEVEL],
byte[(uint8_t)LM2755DevReg::D3_DELAY],

View File

@ -34,13 +34,13 @@ void LP5562::init()
// currently use this device but is a structure we use elsewhere.
// Note that this assumed that the LED Map register is set to its
// default value.
b = new LEDChannel(
b = NEW_NOTHROW LEDChannel(
byte[(uint8_t)LP5562DevReg::B_PWM]
);
g = new LEDChannel(
g = NEW_NOTHROW LEDChannel(
byte[(uint8_t)LP5562DevReg::G_PWM]
);
r = new LEDChannel(
r = NEW_NOTHROW LEDChannel(
byte[(uint8_t)LP5562DevReg::R_PWM]
);

View File

@ -260,7 +260,7 @@ bool Morse::parse_sensors(const char *json)
bool Morse::connect_sockets(void)
{
if (!sensors_sock) {
sensors_sock = new SocketAPM_native(false);
sensors_sock = NEW_NOTHROW SocketAPM_native(false);
if (!sensors_sock) {
AP_HAL::panic("Out of memory for sensors socket");
}
@ -279,7 +279,7 @@ bool Morse::connect_sockets(void)
printf("Sensors connected\n");
}
if (!control_sock) {
control_sock = new SocketAPM_native(false);
control_sock = NEW_NOTHROW SocketAPM_native(false);
if (!control_sock) {
AP_HAL::panic("Out of memory for control socket");
}

View File

@ -43,7 +43,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Morse(frame_str);
return NEW_NOTHROW Morse(frame_str);
}
private:

View File

@ -34,7 +34,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new MotorBoat(frame_str);
return NEW_NOTHROW MotorBoat(frame_str);
}
};

View File

@ -36,7 +36,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new MultiCopter(frame_str);
return NEW_NOTHROW MultiCopter(frame_str);
}
protected:

View File

@ -33,7 +33,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new NoVehicle(frame_str);
return NEW_NOTHROW NoVehicle(frame_str);
}
};

View File

@ -36,7 +36,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Plane(frame_str);
return NEW_NOTHROW Plane(frame_str);
}
protected:

View File

@ -36,7 +36,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new QuadPlane(frame_str);
return NEW_NOTHROW QuadPlane(frame_str);
}
private:

View File

@ -17,7 +17,7 @@ void SIM_RGBLED::update_thread(void)
sf::RenderWindow *w = nullptr;
{
WITH_SEMAPHORE(AP::notify().sf_window_mutex);
w = new sf::RenderWindow(sf::VideoMode(width, height), name);
w = NEW_NOTHROW sf::RenderWindow(sf::VideoMode(width, height), name);
}
if (w == nullptr) {

View File

@ -34,7 +34,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new SimRover(frame_str);
return NEW_NOTHROW SimRover(frame_str);
}
private:

View File

@ -34,7 +34,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Sailboat(frame_str);
return NEW_NOTHROW Sailboat(frame_str);
}
bool on_ground() const override {return true;};

View File

@ -46,7 +46,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Scrimmage(frame_str);
return NEW_NOTHROW Scrimmage(frame_str);
}
/* Create and set in/out socket for extenal simulator */

View File

@ -29,8 +29,8 @@ using namespace SITL;
SerialDevice::SerialDevice(uint16_t tx_bufsize, uint16_t rx_bufsize)
{
to_autopilot = new ByteBuffer{tx_bufsize};
from_autopilot = new ByteBuffer{rx_bufsize};
to_autopilot = NEW_NOTHROW ByteBuffer{tx_bufsize};
from_autopilot = NEW_NOTHROW ByteBuffer{rx_bufsize};
}
bool SerialDevice::init_sitl_pointer()

View File

@ -41,7 +41,7 @@ public:
/* Static object creator */
static Aircraft *create(const char *frame_str) {
return new SilentWings(frame_str);
return NEW_NOTHROW SilentWings(frame_str);
}
private:

View File

@ -35,7 +35,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new SingleCopter(frame_str);
return NEW_NOTHROW SingleCopter(frame_str);
}
private:

View File

@ -40,7 +40,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new StratoBlimp(frame_str);
return NEW_NOTHROW StratoBlimp(frame_str);
}
static const struct AP_Param::GroupInfo var_info[];

View File

@ -51,7 +51,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Submarine(frame_str);
return NEW_NOTHROW Submarine(frame_str);
}

View File

@ -33,7 +33,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Tracker(frame_str);
return NEW_NOTHROW Tracker(frame_str);
}
private:

View File

@ -290,7 +290,7 @@ bool Webots::parse_sensors(const char *json)
bool Webots::connect_sockets(void)
{
if (!sim_sock) {
sim_sock = new SocketAPM_native(false);
sim_sock = NEW_NOTHROW SocketAPM_native(false);
if (!sim_sock) {
AP_HAL::panic("Out of memory for sensors socket");
}

View File

@ -47,7 +47,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new Webots(frame_str);
return NEW_NOTHROW Webots(frame_str);
}

View File

@ -43,7 +43,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new WebotsPython(frame_str);
return NEW_NOTHROW WebotsPython(frame_str);
}
/* Create and set in/out socket for Webots simulator */

View File

@ -125,7 +125,7 @@ XPlane::XPlane(const char *frame_str) :
*/
void XPlane::add_dref(const char *name, DRefType type, const AP_JSON::value &dref)
{
struct DRef *d = new struct DRef;
struct DRef *d = NEW_NOTHROW struct DRef;
if (d == nullptr) {
AP_HAL::panic("out of memory for DRef %s", name);
}
@ -151,7 +151,7 @@ void XPlane::add_dref(const char *name, DRefType type, const AP_JSON::value &dre
void XPlane::add_joyinput(const char *label, JoyType type, const AP_JSON::value &d)
{
if (strncmp(label, "axis", 4) == 0) {
struct JoyInput *j = new struct JoyInput;
struct JoyInput *j = NEW_NOTHROW struct JoyInput;
if (j == nullptr) {
AP_HAL::panic("out of memory for JoyInput %s", label);
}
@ -164,7 +164,7 @@ void XPlane::add_joyinput(const char *label, JoyType type, const AP_JSON::value
joyinputs = j;
}
if (strncmp(label, "button", 6) == 0) {
struct JoyInput *j = new struct JoyInput;
struct JoyInput *j = NEW_NOTHROW struct JoyInput;
if (j == nullptr) {
AP_HAL::panic("out of memory for JoyInput %s", label);
}

View File

@ -46,7 +46,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new XPlane(frame_str);
return NEW_NOTHROW XPlane(frame_str);
}
private:

View File

@ -44,7 +44,7 @@ public:
/* static object creator */
static Aircraft *create(const char *frame_str) {
return new last_letter(frame_str);
return NEW_NOTHROW last_letter(frame_str);
}
private:

View File

@ -81,7 +81,7 @@ float ServoModel::apply_filter(float v, float dt)
if (sitl->servo.servo_delay > 0) {
uint32_t delay_len = MAX(1,sitl->servo.servo_delay * sitl->loop_rate_hz);
if (!delay) {
delay = new ObjectBuffer<float>();
delay = NEW_NOTHROW ObjectBuffer<float>();
}
if (delay->get_size() != delay_len) {
delay->set_size(delay_len);