mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
9ace1c6792
commit
72dc87e5c1
|
@ -547,7 +547,7 @@ void AP_Baro::init(void)
|
||||||
#if !AP_TEST_DRONECAN_DRIVERS
|
#if !AP_TEST_DRONECAN_DRIVERS
|
||||||
// use dronecan instances instead of SITL instances
|
// use dronecan instances instead of SITL instances
|
||||||
for(uint8_t i = 0; i < sitl->baro_count; i++) {
|
for(uint8_t i = 0; i < sitl->baro_count; i++) {
|
||||||
ADD_BACKEND(new AP_Baro_SITL(*this));
|
ADD_BACKEND(NEW_NOTHROW AP_Baro_SITL(*this));
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
@ -562,7 +562,7 @@ void AP_Baro::init(void)
|
||||||
#if AP_BARO_EXTERNALAHRS_ENABLED
|
#if AP_BARO_EXTERNALAHRS_ENABLED
|
||||||
const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::BARO);
|
const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::BARO);
|
||||||
if (serial_port >= 0) {
|
if (serial_port >= 0) {
|
||||||
ADD_BACKEND(new AP_Baro_ExternalAHRS(*this, serial_port));
|
ADD_BACKEND(NEW_NOTHROW AP_Baro_ExternalAHRS(*this, serial_port));
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -716,7 +716,7 @@ void AP_Baro::init(void)
|
||||||
}
|
}
|
||||||
for (uint8_t i=0; i<8; i++) {
|
for (uint8_t i=0; i<8; i++) {
|
||||||
if (msp_instance_mask & (1U<<i)) {
|
if (msp_instance_mask & (1U<<i)) {
|
||||||
ADD_BACKEND(new AP_Baro_MSP(*this, i));
|
ADD_BACKEND(NEW_NOTHROW AP_Baro_MSP(*this, i));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -48,7 +48,7 @@ AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::De
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Baro_BMP085 *sensor = new AP_Baro_BMP085(baro, std::move(dev));
|
AP_Baro_BMP085 *sensor = NEW_NOTHROW AP_Baro_BMP085(baro, std::move(dev));
|
||||||
if (!sensor || !sensor->_init()) {
|
if (!sensor || !sensor->_init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -60,7 +60,7 @@ AP_Baro_Backend *AP_Baro_BMP280::probe(AP_Baro &baro,
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Baro_BMP280 *sensor = new AP_Baro_BMP280(baro, std::move(dev));
|
AP_Baro_BMP280 *sensor = NEW_NOTHROW AP_Baro_BMP280(baro, std::move(dev));
|
||||||
if (!sensor || !sensor->_init()) {
|
if (!sensor || !sensor->_init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -66,7 +66,7 @@ AP_Baro_Backend *AP_Baro_BMP388::probe(AP_Baro &baro,
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Baro_BMP388 *sensor = new AP_Baro_BMP388(baro, std::move(_dev));
|
AP_Baro_BMP388 *sensor = NEW_NOTHROW AP_Baro_BMP388(baro, std::move(_dev));
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -56,7 +56,7 @@ AP_Baro_Backend *AP_Baro_DPS280::probe(AP_Baro &baro,
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Baro_DPS280 *sensor = new AP_Baro_DPS280(baro, std::move(_dev));
|
AP_Baro_DPS280 *sensor = NEW_NOTHROW AP_Baro_DPS280(baro, std::move(_dev));
|
||||||
if (sensor) {
|
if (sensor) {
|
||||||
sensor->is_dps310 = _is_dps310;
|
sensor->is_dps310 = _is_dps310;
|
||||||
}
|
}
|
||||||
|
|
|
@ -42,7 +42,7 @@ AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro)
|
||||||
AP_Baro_DroneCAN* backend = nullptr;
|
AP_Baro_DroneCAN* backend = nullptr;
|
||||||
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
|
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
|
||||||
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) {
|
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) {
|
||||||
backend = new AP_Baro_DroneCAN(baro);
|
backend = NEW_NOTHROW AP_Baro_DroneCAN(baro);
|
||||||
if (backend == nullptr) {
|
if (backend == nullptr) {
|
||||||
AP::can().log_text(AP_CANManager::LOG_ERROR,
|
AP::can().log_text(AP_CANManager::LOG_ERROR,
|
||||||
LOG_TAG,
|
LOG_TAG,
|
||||||
|
|
|
@ -14,7 +14,7 @@ public:
|
||||||
AP_Baro_Dummy(AP_Baro &baro);
|
AP_Baro_Dummy(AP_Baro &baro);
|
||||||
void update(void) override;
|
void update(void) override;
|
||||||
static AP_Baro_Backend *probe(AP_Baro &baro) {
|
static AP_Baro_Backend *probe(AP_Baro &baro) {
|
||||||
return new AP_Baro_Dummy(baro);
|
return NEW_NOTHROW AP_Baro_Dummy(baro);
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -48,7 +48,7 @@ AP_Baro_Backend *AP_Baro_FBM320::probe(AP_Baro &baro,
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Baro_FBM320 *sensor = new AP_Baro_FBM320(baro, std::move(_dev));
|
AP_Baro_FBM320 *sensor = NEW_NOTHROW AP_Baro_FBM320(baro, std::move(_dev));
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -80,7 +80,7 @@ AP_Baro_Backend *AP_Baro_ICM20789::probe(AP_Baro &baro,
|
||||||
if (!dev || !dev_imu) {
|
if (!dev || !dev_imu) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
AP_Baro_ICM20789 *sensor = new AP_Baro_ICM20789(baro, std::move(dev), std::move(dev_imu));
|
AP_Baro_ICM20789 *sensor = NEW_NOTHROW AP_Baro_ICM20789(baro, std::move(dev), std::move(dev_imu));
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -61,7 +61,7 @@ AP_Baro_Backend *AP_Baro_ICP101XX::probe(AP_Baro &baro,
|
||||||
if (!dev) {
|
if (!dev) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
AP_Baro_ICP101XX *sensor = new AP_Baro_ICP101XX(baro, std::move(dev));
|
AP_Baro_ICP101XX *sensor = NEW_NOTHROW AP_Baro_ICP101XX(baro, std::move(dev));
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -87,7 +87,7 @@ AP_Baro_Backend *AP_Baro_ICP201XX::probe(AP_Baro &baro,
|
||||||
if (!dev) {
|
if (!dev) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
AP_Baro_ICP201XX *sensor = new AP_Baro_ICP201XX(baro, std::move(dev));
|
AP_Baro_ICP201XX *sensor = NEW_NOTHROW AP_Baro_ICP201XX(baro, std::move(dev));
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -55,7 +55,7 @@ AP_Baro_Backend *AP_Baro_KellerLD::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::D
|
||||||
if (!dev) {
|
if (!dev) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
AP_Baro_KellerLD *sensor = new AP_Baro_KellerLD(baro, std::move(dev));
|
AP_Baro_KellerLD *sensor = NEW_NOTHROW AP_Baro_KellerLD(baro, std::move(dev));
|
||||||
if (!sensor || !sensor->_init()) {
|
if (!sensor || !sensor->_init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -69,7 +69,7 @@ AP_Baro_Backend *AP_Baro_LPS2XH::probe(AP_Baro &baro,
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Baro_LPS2XH *sensor = new AP_Baro_LPS2XH(baro, std::move(dev));
|
AP_Baro_LPS2XH *sensor = NEW_NOTHROW AP_Baro_LPS2XH(baro, std::move(dev));
|
||||||
if (!sensor || !sensor->_init()) {
|
if (!sensor || !sensor->_init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
@ -86,7 +86,7 @@ AP_Baro_Backend *AP_Baro_LPS2XH::probe_InvensenseIMU(AP_Baro &baro,
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Baro_LPS2XH *sensor = new AP_Baro_LPS2XH(baro, std::move(dev));
|
AP_Baro_LPS2XH *sensor = NEW_NOTHROW AP_Baro_LPS2XH(baro, std::move(dev));
|
||||||
if (sensor) {
|
if (sensor) {
|
||||||
if (!sensor->_imu_i2c_init(imu_address)) {
|
if (!sensor->_imu_i2c_init(imu_address)) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
|
|
|
@ -71,7 +71,7 @@ AP_Baro_Backend *AP_Baro_MS56XX::probe(AP_Baro &baro,
|
||||||
if (!dev) {
|
if (!dev) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
AP_Baro_MS56XX *sensor = new AP_Baro_MS56XX(baro, std::move(dev), ms56xx_type);
|
AP_Baro_MS56XX *sensor = NEW_NOTHROW AP_Baro_MS56XX(baro, std::move(dev), ms56xx_type);
|
||||||
if (!sensor || !sensor->_init()) {
|
if (!sensor || !sensor->_init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
|
@ -86,7 +86,7 @@ AP_Baro_Backend *AP_Baro_SPL06::probe(AP_Baro &baro,
|
||||||
dev->set_read_flag(0x80);
|
dev->set_read_flag(0x80);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Baro_SPL06 *sensor = new AP_Baro_SPL06(baro, std::move(dev));
|
AP_Baro_SPL06 *sensor = NEW_NOTHROW AP_Baro_SPL06(baro, std::move(dev));
|
||||||
if (!sensor || !sensor->_init()) {
|
if (!sensor || !sensor->_init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
|
Loading…
Reference in New Issue