mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
5130e26f4c
commit
8554081be5
|
@ -386,14 +386,14 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
|||
// to ease moving from PX4 to ChibiOS we'll lie a little about
|
||||
// the backend driver...
|
||||
if (AP_RangeFinder_PWM::detect()) {
|
||||
_add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#if AP_RANGEFINDER_BBB_PRU_ENABLED
|
||||
case Type::BBB_PRU:
|
||||
if (AP_RangeFinder_BBB_PRU::detect()) {
|
||||
_add_backend(new AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
@ -415,14 +415,14 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
|||
#if AP_RANGEFINDER_BEBOP_ENABLED
|
||||
case Type::BEBOP:
|
||||
if (AP_RangeFinder_Bebop::detect()) {
|
||||
_add_backend(new AP_RangeFinder_Bebop(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_Bebop(state[instance], params[instance]), instance);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#if AP_RANGEFINDER_MAVLINK_ENABLED
|
||||
case Type::MAVLink:
|
||||
if (AP_RangeFinder_MAVLink::detect()) {
|
||||
_add_backend(new AP_RangeFinder_MAVLink(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_MAVLink(state[instance], params[instance]), instance);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
@ -435,7 +435,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
|||
case Type::ANALOG:
|
||||
// note that analog will always come back as present if the pin is valid
|
||||
if (AP_RangeFinder_analog::detect(params[instance])) {
|
||||
_add_backend(new AP_RangeFinder_analog(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_analog(state[instance], params[instance]), instance);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
@ -443,7 +443,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
|||
case Type::HC_SR04:
|
||||
// note that this will always come back as present if the pin is valid
|
||||
if (AP_RangeFinder_HC_SR04::detect(params[instance])) {
|
||||
_add_backend(new AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
@ -480,7 +480,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
|||
#if AP_RANGEFINDER_PWM_ENABLED
|
||||
case Type::PWM:
|
||||
if (AP_RangeFinder_PWM::detect()) {
|
||||
_add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
@ -519,32 +519,32 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
|||
|
||||
#if AP_RANGEFINDER_SIM_ENABLED
|
||||
case Type::SIM:
|
||||
_add_backend(new AP_RangeFinder_SITL(state[instance], params[instance], instance), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_SITL(state[instance], params[instance], instance), instance);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||
case Type::MSP:
|
||||
if (AP_RangeFinder_MSP::detect()) {
|
||||
_add_backend(new AP_RangeFinder_MSP(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_MSP(state[instance], params[instance]), instance);
|
||||
}
|
||||
break;
|
||||
#endif // HAL_MSP_RANGEFINDER_ENABLED
|
||||
|
||||
#if AP_RANGEFINDER_USD1_CAN_ENABLED
|
||||
case Type::USD1_CAN:
|
||||
_add_backend(new AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
|
||||
case Type::Benewake_CAN:
|
||||
_add_backend(new AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_LUA_ENABLED
|
||||
case Type::Lua_Scripting:
|
||||
_add_backend(new AP_RangeFinder_Lua(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_Lua(state[instance], params[instance]), instance);
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
@ -562,12 +562,12 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
|||
|
||||
#if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED
|
||||
case Type::TOFSenseP_CAN:
|
||||
_add_backend(new AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_RANGEFINDER_NRA24_CAN_ENABLED
|
||||
case Type::NRA24_CAN:
|
||||
_add_backend(new AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance);
|
||||
_add_backend(NEW_NOTHROW AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED
|
||||
|
|
|
@ -22,7 +22,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_Ainstein_LR_D1(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_Ainstein_LR_D1(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -124,7 +124,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_BLPing(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_BLPing(_state, _params);
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
|
@ -45,7 +45,7 @@ AP_RangeFinder_Backend_CAN::AP_RangeFinder_Backend_CAN(
|
|||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
state.var_info = var_info;
|
||||
multican_rangefinder = new MultiCAN{FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Backend_CAN::handle_frame, bool, AP_HAL::CANFrame &), can_type, driver_name};
|
||||
multican_rangefinder = NEW_NOTHROW MultiCAN{FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Backend_CAN::handle_frame, bool, AP_HAL::CANFrame &), can_type, driver_name};
|
||||
if (multican_rangefinder == nullptr) {
|
||||
AP_BoardConfig::allocation_error("Failed to create rangefinder multican");
|
||||
}
|
||||
|
|
|
@ -64,7 +64,7 @@ static const uint16_t waveform_mode1[32] = {
|
|||
|
||||
AP_RangeFinder_Bebop::AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
|
||||
AP_RangeFinder_Backend(_state, _params),
|
||||
_thread(new Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void)))
|
||||
_thread(NEW_NOTHROW Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void)))
|
||||
{
|
||||
_init();
|
||||
_freq = RNFD_BEBOP_DEFAULT_FREQ;
|
||||
|
|
|
@ -13,7 +13,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_Benewake_TF02(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_Benewake_TF02(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -13,7 +13,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_Benewake_TF03(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_Benewake_TF03(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -13,7 +13,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_Benewake_TFMini(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_Benewake_TFMini(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -56,7 +56,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_Benewake_TFMiniPlus::detect(
|
|||
}
|
||||
|
||||
AP_RangeFinder_Benewake_TFMiniPlus *sensor
|
||||
= new AP_RangeFinder_Benewake_TFMiniPlus(_state, _params, std::move(dev));
|
||||
= NEW_NOTHROW AP_RangeFinder_Benewake_TFMiniPlus(_state, _params, std::move(dev));
|
||||
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
|
|
|
@ -60,7 +60,7 @@ AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_dronecan_backend(AP_DroneC
|
|||
//it up as UAVCAN type
|
||||
return nullptr;
|
||||
}
|
||||
frontend.drivers[i] = new AP_RangeFinder_DroneCAN(frontend.state[i], frontend.params[i]);
|
||||
frontend.drivers[i] = NEW_NOTHROW AP_RangeFinder_DroneCAN(frontend.state[i], frontend.params[i]);
|
||||
driver = (AP_RangeFinder_DroneCAN*)frontend.drivers[i];
|
||||
if (driver == nullptr) {
|
||||
break;
|
||||
|
|
|
@ -15,7 +15,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_GYUS42v2(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_GYUS42v2(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -70,7 +70,7 @@ public:
|
|||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params)
|
||||
{
|
||||
return new AP_RangeFinder_JRE_Serial(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_JRE_Serial(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -15,7 +15,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_Lanbao(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_Lanbao(_state, _params);
|
||||
}
|
||||
|
||||
// Lanbao is always 115200:
|
||||
|
|
|
@ -49,7 +49,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_LeddarOne(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_LeddarOne(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -17,7 +17,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_LeddarVu8(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_LeddarVu8(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -81,7 +81,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder::RangeFi
|
|||
}
|
||||
|
||||
AP_RangeFinder_LightWareI2C *sensor
|
||||
= new AP_RangeFinder_LightWareI2C(_state, _params, std::move(dev));
|
||||
= NEW_NOTHROW AP_RangeFinder_LightWareI2C(_state, _params, std::move(dev));
|
||||
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
|
|
|
@ -15,7 +15,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_LightWareSerial(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_LightWareSerial(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -54,7 +54,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeF
|
|||
}
|
||||
|
||||
AP_RangeFinder_MaxsonarI2CXL *sensor
|
||||
= new AP_RangeFinder_MaxsonarI2CXL(_state, _params, std::move(dev));
|
||||
= NEW_NOTHROW AP_RangeFinder_MaxsonarI2CXL(_state, _params, std::move(dev));
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
}
|
||||
|
|
|
@ -15,7 +15,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_MaxsonarSerialLV(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_MaxsonarSerialLV(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -30,7 +30,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_NMEA(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_NMEA(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -14,7 +14,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_NoopLoop(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_NoopLoop(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -62,7 +62,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_PulsedLightLRF::detect(uint8_t bus,
|
|||
RangeFinder::Type rftype)
|
||||
{
|
||||
AP_RangeFinder_PulsedLightLRF *sensor
|
||||
= new AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype);
|
||||
= NEW_NOTHROW AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype);
|
||||
if (!sensor ||
|
||||
!sensor->init()) {
|
||||
delete sensor;
|
||||
|
|
|
@ -35,7 +35,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_RDS02UF(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_RDS02UF(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -47,7 +47,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_TOFSenseF_I2C::detect(RangeFinder::RangeF
|
|||
}
|
||||
|
||||
AP_RangeFinder_TOFSenseF_I2C *sensor
|
||||
= new AP_RangeFinder_TOFSenseF_I2C(_state, _params, std::move(dev));
|
||||
= NEW_NOTHROW AP_RangeFinder_TOFSenseF_I2C(_state, _params, std::move(dev));
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
}
|
||||
|
|
|
@ -53,7 +53,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_TeraRangerI2C::detect(RangeFinder::RangeF
|
|||
return nullptr;
|
||||
}
|
||||
|
||||
AP_RangeFinder_TeraRangerI2C *sensor = new AP_RangeFinder_TeraRangerI2C(_state, _params, std::move(i2c_dev));
|
||||
AP_RangeFinder_TeraRangerI2C *sensor = NEW_NOTHROW AP_RangeFinder_TeraRangerI2C(_state, _params, std::move(i2c_dev));
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
}
|
||||
|
|
|
@ -15,7 +15,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_TeraRanger_Serial(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_TeraRanger_Serial(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -15,7 +15,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_USD1_Serial(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_USD1_Serial(_state, _params);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
|
|
@ -229,7 +229,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_VL53L0X::detect(RangeFinder::RangeFinder_
|
|||
return nullptr;
|
||||
}
|
||||
AP_RangeFinder_VL53L0X *sensor
|
||||
= new AP_RangeFinder_VL53L0X(_state, _params, std::move(dev));
|
||||
= NEW_NOTHROW AP_RangeFinder_VL53L0X(_state, _params, std::move(dev));
|
||||
|
||||
if (!sensor) {
|
||||
delete sensor;
|
||||
|
|
|
@ -48,7 +48,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_VL53L1X::detect(RangeFinder::RangeFinder_
|
|||
}
|
||||
|
||||
AP_RangeFinder_VL53L1X *sensor
|
||||
= new AP_RangeFinder_VL53L1X(_state, _params, std::move(dev));
|
||||
= NEW_NOTHROW AP_RangeFinder_VL53L1X(_state, _params, std::move(dev));
|
||||
|
||||
if (!sensor) {
|
||||
delete sensor;
|
||||
|
|
|
@ -17,7 +17,7 @@ public:
|
|||
static AP_RangeFinder_Backend_Serial *create(
|
||||
RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params) {
|
||||
return new AP_RangeFinder_Wasp(_state, _params);
|
||||
return NEW_NOTHROW AP_RangeFinder_Wasp(_state, _params);
|
||||
}
|
||||
|
||||
void update(void) override;
|
||||
|
|
Loading…
Reference in New Issue