mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
54017b820b
commit
8fdf085e2f
|
@ -356,67 +356,67 @@ void AP_Airspeed::allocate()
|
|||
break;
|
||||
case TYPE_I2C_MS4525:
|
||||
#if AP_AIRSPEED_MS4525_ENABLED
|
||||
sensor[i] = new AP_Airspeed_MS4525(*this, i);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_MS4525(*this, i);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_SITL:
|
||||
#if AP_AIRSPEED_SITL_ENABLED
|
||||
sensor[i] = new AP_Airspeed_SITL(*this, i);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_SITL(*this, i);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_ANALOG:
|
||||
#if AP_AIRSPEED_ANALOG_ENABLED
|
||||
sensor[i] = new AP_Airspeed_Analog(*this, i);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_Analog(*this, i);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_MS5525:
|
||||
#if AP_AIRSPEED_MS5525_ENABLED
|
||||
sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_MS5525_ADDRESS_1:
|
||||
#if AP_AIRSPEED_MS5525_ENABLED
|
||||
sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_MS5525_ADDRESS_2:
|
||||
#if AP_AIRSPEED_MS5525_ENABLED
|
||||
sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_SDP3X:
|
||||
#if AP_AIRSPEED_SDP3X_ENABLED
|
||||
sensor[i] = new AP_Airspeed_SDP3X(*this, i);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_SDP3X(*this, i);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_DLVR_5IN:
|
||||
#if AP_AIRSPEED_DLVR_ENABLED
|
||||
sensor[i] = new AP_Airspeed_DLVR(*this, i, 5);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 5);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_DLVR_10IN:
|
||||
#if AP_AIRSPEED_DLVR_ENABLED
|
||||
sensor[i] = new AP_Airspeed_DLVR(*this, i, 10);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 10);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_DLVR_20IN:
|
||||
#if AP_AIRSPEED_DLVR_ENABLED
|
||||
sensor[i] = new AP_Airspeed_DLVR(*this, i, 20);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 20);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_DLVR_30IN:
|
||||
#if AP_AIRSPEED_DLVR_ENABLED
|
||||
sensor[i] = new AP_Airspeed_DLVR(*this, i, 30);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 30);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_I2C_DLVR_60IN:
|
||||
#if AP_AIRSPEED_DLVR_ENABLED
|
||||
sensor[i] = new AP_Airspeed_DLVR(*this, i, 60);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 60);
|
||||
#endif // AP_AIRSPEED_DLVR_ENABLED
|
||||
break;
|
||||
case TYPE_I2C_ASP5033:
|
||||
#if AP_AIRSPEED_ASP5033_ENABLED
|
||||
sensor[i] = new AP_Airspeed_ASP5033(*this, i);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_ASP5033(*this, i);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_UAVCAN:
|
||||
|
@ -427,18 +427,18 @@ void AP_Airspeed::allocate()
|
|||
case TYPE_NMEA_WATER:
|
||||
#if AP_AIRSPEED_NMEA_ENABLED
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
|
||||
sensor[i] = new AP_Airspeed_NMEA(*this, i);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_NMEA(*this, i);
|
||||
#endif
|
||||
#endif
|
||||
break;
|
||||
case TYPE_MSP:
|
||||
#if AP_AIRSPEED_MSP_ENABLED
|
||||
sensor[i] = new AP_Airspeed_MSP(*this, i, 0);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_MSP(*this, i, 0);
|
||||
#endif
|
||||
break;
|
||||
case TYPE_EXTERNAL:
|
||||
#if AP_AIRSPEED_EXTERNAL_ENABLED
|
||||
sensor[i] = new AP_Airspeed_External(*this, i);
|
||||
sensor[i] = NEW_NOTHROW AP_Airspeed_External(*this, i);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -50,7 +50,7 @@ AP_Airspeed_Backend *AP_Airspeed_DLVR::probe(AP_Airspeed &_frontend,
|
|||
if (!_dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Airspeed_DLVR *sensor = new AP_Airspeed_DLVR(_frontend, _instance, _range_inH2O);
|
||||
AP_Airspeed_DLVR *sensor = NEW_NOTHROW AP_Airspeed_DLVR(_frontend, _instance, _range_inH2O);
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
}
|
||||
|
|
|
@ -45,7 +45,7 @@ AP_Airspeed_Backend* AP_Airspeed_DroneCAN::probe(AP_Airspeed &_frontend, uint8_t
|
|||
// match with previous ID only
|
||||
continue;
|
||||
}
|
||||
backend = new AP_Airspeed_DroneCAN(_frontend, _instance);
|
||||
backend = NEW_NOTHROW AP_Airspeed_DroneCAN(_frontend, _instance);
|
||||
if (backend == nullptr) {
|
||||
AP::can().log_text(AP_CANManager::LOG_INFO,
|
||||
LOG_TAG,
|
||||
|
|
Loading…
Reference in New Issue