mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_InertialSensor: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
17e338d7f6
commit
a0acccb1f9
@ -721,7 +721,7 @@ AP_InertialSensor::AP_InertialSensor() :
|
||||
AP_InertialSensor *AP_InertialSensor::get_singleton()
|
||||
{
|
||||
if (!_singleton) {
|
||||
_singleton = new AP_InertialSensor();
|
||||
_singleton = NEW_NOTHROW AP_InertialSensor();
|
||||
}
|
||||
return _singleton;
|
||||
}
|
||||
@ -1157,7 +1157,7 @@ AP_InertialSensor::detect_backends(void)
|
||||
// if enabled, make the first IMU the external AHRS
|
||||
const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::IMU);
|
||||
if (serial_port >= 0) {
|
||||
ADD_BACKEND(new AP_InertialSensor_ExternalAHRS(*this, serial_port));
|
||||
ADD_BACKEND(NEW_NOTHROW AP_InertialSensor_ExternalAHRS(*this, serial_port));
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -2279,10 +2279,10 @@ void AP_InertialSensor::acal_init()
|
||||
{
|
||||
// NOTE: these objects are never deallocated because the pre-arm checks force a reboot
|
||||
if (_acal == nullptr) {
|
||||
_acal = new AP_AccelCal;
|
||||
_acal = NEW_NOTHROW AP_AccelCal;
|
||||
}
|
||||
if (_accel_calibrator == nullptr) {
|
||||
_accel_calibrator = new AccelCalibrator[INS_MAX_INSTANCES];
|
||||
_accel_calibrator = NEW_NOTHROW AccelCalibrator[INS_MAX_INSTANCES];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -89,7 +89,7 @@ AP_InertialSensor_ADIS1647x::probe(AP_InertialSensor &imu,
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
auto sensor = new AP_InertialSensor_ADIS1647x(imu, std::move(dev), rotation, drdy_gpio);
|
||||
auto sensor = NEW_NOTHROW AP_InertialSensor_ADIS1647x(imu, std::move(dev), rotation, drdy_gpio);
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
|
@ -85,7 +85,7 @@ AP_InertialSensor_BMI055::probe(AP_InertialSensor &imu,
|
||||
if (!dev_accel || !dev_gyro) {
|
||||
return nullptr;
|
||||
}
|
||||
auto sensor = new AP_InertialSensor_BMI055(imu, std::move(dev_accel), std::move(dev_gyro), rotation);
|
||||
auto sensor = NEW_NOTHROW AP_InertialSensor_BMI055(imu, std::move(dev_accel), std::move(dev_gyro), rotation);
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
|
@ -84,7 +84,7 @@ AP_InertialSensor_BMI088::probe(AP_InertialSensor &imu,
|
||||
if (!dev_accel || !dev_gyro) {
|
||||
return nullptr;
|
||||
}
|
||||
auto sensor = new AP_InertialSensor_BMI088(imu, std::move(dev_accel), std::move(dev_gyro), rotation);
|
||||
auto sensor = NEW_NOTHROW AP_InertialSensor_BMI088(imu, std::move(dev_accel), std::move(dev_gyro), rotation);
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
|
@ -135,7 +135,7 @@ AP_InertialSensor_BMI160::probe(AP_InertialSensor &imu,
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
auto sensor = new AP_InertialSensor_BMI160(imu, std::move(dev), rotation);
|
||||
auto sensor = NEW_NOTHROW AP_InertialSensor_BMI160(imu, std::move(dev), rotation);
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
@ -157,7 +157,7 @@ AP_InertialSensor_BMI160::probe(AP_InertialSensor &imu,
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
auto sensor = new AP_InertialSensor_BMI160(imu, std::move(dev), rotation);
|
||||
auto sensor = NEW_NOTHROW AP_InertialSensor_BMI160(imu, std::move(dev), rotation);
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
|
@ -164,7 +164,7 @@ AP_InertialSensor_BMI270::probe(AP_InertialSensor &imu,
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
auto sensor = new AP_InertialSensor_BMI270(imu, std::move(dev), rotation);
|
||||
auto sensor = NEW_NOTHROW AP_InertialSensor_BMI270(imu, std::move(dev), rotation);
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
@ -186,7 +186,7 @@ AP_InertialSensor_BMI270::probe(AP_InertialSensor &imu,
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
auto sensor = new AP_InertialSensor_BMI270(imu, std::move(dev), rotation);
|
||||
auto sensor = NEW_NOTHROW AP_InertialSensor_BMI270(imu, std::move(dev), rotation);
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
|
@ -114,7 +114,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensense::probe(AP_InertialSensor
|
||||
return nullptr;
|
||||
}
|
||||
AP_InertialSensor_Invensense *sensor =
|
||||
new AP_InertialSensor_Invensense(imu, std::move(dev), rotation);
|
||||
NEW_NOTHROW AP_InertialSensor_Invensense(imu, std::move(dev), rotation);
|
||||
if (!sensor || !sensor->_init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -140,7 +140,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensense::probe(AP_InertialSensor
|
||||
|
||||
dev->set_read_flag(0x80);
|
||||
|
||||
sensor = new AP_InertialSensor_Invensense(imu, std::move(dev), rotation);
|
||||
sensor = NEW_NOTHROW AP_InertialSensor_Invensense(imu, std::move(dev), rotation);
|
||||
if (!sensor || !sensor->_init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -502,7 +502,7 @@ AuxiliaryBus *AP_InertialSensor_Invensense::get_auxiliary_bus()
|
||||
}
|
||||
|
||||
if (_has_auxiliary_bus()) {
|
||||
_auxiliary_bus = new AP_Invensense_AuxiliaryBus(*this, _dev->get_bus_id());
|
||||
_auxiliary_bus = NEW_NOTHROW AP_Invensense_AuxiliaryBus(*this, _dev->get_bus_id());
|
||||
}
|
||||
|
||||
return _auxiliary_bus;
|
||||
@ -1204,7 +1204,7 @@ AuxiliaryBusSlave *AP_Invensense_AuxiliaryBus::_instantiate_slave(uint8_t addr,
|
||||
_configure_slaves();
|
||||
}
|
||||
|
||||
return new AP_Invensense_AuxiliaryBusSlave(*this, addr, instance);
|
||||
return NEW_NOTHROW AP_Invensense_AuxiliaryBusSlave(*this, addr, instance);
|
||||
}
|
||||
|
||||
void AP_Invensense_AuxiliaryBus::_configure_slaves()
|
||||
|
@ -94,7 +94,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensensev2::probe(AP_InertialSens
|
||||
return nullptr;
|
||||
}
|
||||
AP_InertialSensor_Invensensev2 *sensor =
|
||||
new AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation);
|
||||
NEW_NOTHROW AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation);
|
||||
if (!sensor || !sensor->_init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -116,7 +116,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensensev2::probe(AP_InertialSens
|
||||
|
||||
dev->set_read_flag(0x80);
|
||||
|
||||
sensor = new AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation);
|
||||
sensor = NEW_NOTHROW AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation);
|
||||
if (!sensor || !sensor->_init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -293,7 +293,7 @@ AuxiliaryBus *AP_InertialSensor_Invensensev2::get_auxiliary_bus()
|
||||
}
|
||||
|
||||
if (_has_auxiliary_bus()) {
|
||||
_auxiliary_bus = new AP_Invensensev2_AuxiliaryBus(*this, _dev->get_bus_id());
|
||||
_auxiliary_bus = NEW_NOTHROW AP_Invensensev2_AuxiliaryBus(*this, _dev->get_bus_id());
|
||||
}
|
||||
|
||||
return _auxiliary_bus;
|
||||
@ -868,7 +868,7 @@ AuxiliaryBusSlave *AP_Invensensev2_AuxiliaryBus::_instantiate_slave(uint8_t addr
|
||||
_configure_slaves();
|
||||
}
|
||||
|
||||
return new AP_Invensensev2_AuxiliaryBusSlave(*this, addr, instance);
|
||||
return NEW_NOTHROW AP_Invensensev2_AuxiliaryBusSlave(*this, addr, instance);
|
||||
}
|
||||
|
||||
void AP_Invensensev2_AuxiliaryBus::_configure_slaves()
|
||||
|
@ -207,7 +207,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensensev3::probe(AP_InertialSens
|
||||
}
|
||||
|
||||
AP_InertialSensor_Invensensev3 *sensor =
|
||||
new AP_InertialSensor_Invensensev3(imu, std::move(_dev), _rotation);
|
||||
NEW_NOTHROW AP_InertialSensor_Invensensev3(imu, std::move(_dev), _rotation);
|
||||
if (!sensor || !sensor->hardware_init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -146,7 +146,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_L3G4200D::probe(AP_InertialSensor &
|
||||
return nullptr;
|
||||
}
|
||||
AP_InertialSensor_L3G4200D *sensor
|
||||
= new AP_InertialSensor_L3G4200D(imu, std::move(dev_gyro), std::move(dev_accel));
|
||||
= NEW_NOTHROW AP_InertialSensor_L3G4200D(imu, std::move(dev_gyro), std::move(dev_accel));
|
||||
if (!sensor || !sensor->_init_sensor()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -402,7 +402,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_LSM9DS0::probe(AP_InertialSensor &_
|
||||
return nullptr;
|
||||
}
|
||||
AP_InertialSensor_LSM9DS0 *sensor =
|
||||
new AP_InertialSensor_LSM9DS0(_imu, std::move(dev_gyro), std::move(dev_accel),
|
||||
NEW_NOTHROW AP_InertialSensor_LSM9DS0(_imu, std::move(dev_gyro), std::move(dev_accel),
|
||||
LSM9DS0_DRY_X_PIN, LSM9DS0_DRY_G_PIN,
|
||||
rotation_a, rotation_g, rotation_gH);
|
||||
if (!sensor || !sensor->_init_sensor()) {
|
||||
|
@ -26,7 +26,7 @@ AP_InertialSensor_NONE::AP_InertialSensor_NONE(AP_InertialSensor &imu, const uin
|
||||
*/
|
||||
AP_InertialSensor_Backend *AP_InertialSensor_NONE::detect(AP_InertialSensor &_imu, const uint16_t sample_rates[])
|
||||
{
|
||||
AP_InertialSensor_NONE *sensor = new AP_InertialSensor_NONE(_imu, sample_rates);
|
||||
AP_InertialSensor_NONE *sensor = NEW_NOTHROW AP_InertialSensor_NONE(_imu, sample_rates);
|
||||
if (sensor == nullptr) {
|
||||
|
||||
return nullptr;
|
||||
|
@ -206,7 +206,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_RST::probe(AP_InertialSensor &imu,
|
||||
return nullptr;
|
||||
}
|
||||
AP_InertialSensor_RST *sensor
|
||||
= new AP_InertialSensor_RST(imu, std::move(dev_gyro), std::move(dev_accel), rotation_g, rotation_a);
|
||||
= NEW_NOTHROW AP_InertialSensor_RST(imu, std::move(dev_gyro), std::move(dev_accel), rotation_g, rotation_a);
|
||||
if (!sensor || !sensor->_init_sensor()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -63,7 +63,7 @@ AP_InertialSensor_Backend* AP_InertialSensor_SCHA63T::probe(AP_InertialSensor &i
|
||||
if (!dev_uno || !dev_due) {
|
||||
return nullptr;
|
||||
}
|
||||
auto sensor = new AP_InertialSensor_SCHA63T(imu, std::move(dev_uno), std::move(dev_due), rotation);
|
||||
auto sensor = NEW_NOTHROW AP_InertialSensor_SCHA63T(imu, std::move(dev_uno), std::move(dev_due), rotation);
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
|
@ -20,7 +20,7 @@ AP_InertialSensor_SITL::AP_InertialSensor_SITL(AP_InertialSensor &imu, const uin
|
||||
*/
|
||||
AP_InertialSensor_Backend *AP_InertialSensor_SITL::detect(AP_InertialSensor &_imu, const uint16_t sample_rates[])
|
||||
{
|
||||
AP_InertialSensor_SITL *sensor = new AP_InertialSensor_SITL(_imu, sample_rates);
|
||||
AP_InertialSensor_SITL *sensor = NEW_NOTHROW AP_InertialSensor_SITL(_imu, sample_rates);
|
||||
if (sensor == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -349,7 +349,7 @@ void AP_InertialSensor_TCal::update_accel_learning(const Vector3f &accel, float
|
||||
return;
|
||||
}
|
||||
if (learn == nullptr && hal.scheduler->is_system_initialized()) {
|
||||
learn = new Learn(*this, temperature);
|
||||
learn = NEW_NOTHROW Learn(*this, temperature);
|
||||
if (learn) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TCAL[%u]: started calibration t=%.1fC tmax=%.1fC",
|
||||
instance()+1,
|
||||
|
Loading…
Reference in New Issue
Block a user