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

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:13 +10:00
parent 014b3bba70
commit 7235c146fa
7 changed files with 10 additions and 10 deletions

View File

@ -141,7 +141,7 @@ void AP_OpticalFlow::init(uint32_t log_bit)
break; break;
case Type::BEBOP: case Type::BEBOP:
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
backend = new AP_OpticalFlow_Onboard(*this); backend = NEW_NOTHROW AP_OpticalFlow_Onboard(*this);
#endif #endif
break; break;
case Type::CXOF: case Type::CXOF:
@ -156,7 +156,7 @@ void AP_OpticalFlow::init(uint32_t log_bit)
break; break;
case Type::UAVCAN: case Type::UAVCAN:
#if AP_OPTICALFLOW_HEREFLOW_ENABLED #if AP_OPTICALFLOW_HEREFLOW_ENABLED
backend = new AP_OpticalFlow_HereFlow(*this); backend = NEW_NOTHROW AP_OpticalFlow_HereFlow(*this);
#endif #endif
break; break;
case Type::MSP: case Type::MSP:
@ -171,7 +171,7 @@ void AP_OpticalFlow::init(uint32_t log_bit)
break; break;
case Type::SITL: case Type::SITL:
#if AP_OPTICALFLOW_SITL_ENABLED #if AP_OPTICALFLOW_SITL_ENABLED
backend = new AP_OpticalFlow_SITL(*this); backend = NEW_NOTHROW AP_OpticalFlow_SITL(*this);
#endif #endif
break; break;
} }
@ -243,7 +243,7 @@ void AP_OpticalFlow::handle_msp(const MSP::msp_opflow_data_message_t &pkt)
void AP_OpticalFlow::start_calibration() void AP_OpticalFlow::start_calibration()
{ {
if (_calibrator == nullptr) { if (_calibrator == nullptr) {
_calibrator = new AP_OpticalFlow_Calibrator(); _calibrator = NEW_NOTHROW AP_OpticalFlow_Calibrator();
if (_calibrator == nullptr) { if (_calibrator == nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "FlowCal: failed to start"); GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "FlowCal: failed to start");
return; return;

View File

@ -72,7 +72,7 @@ AP_OpticalFlow_CXOF *AP_OpticalFlow_CXOF::detect(AP_OpticalFlow &_frontend)
} }
// we have found a serial port so use it // we have found a serial port so use it
AP_OpticalFlow_CXOF *sensor = new AP_OpticalFlow_CXOF(_frontend, uart); AP_OpticalFlow_CXOF *sensor = NEW_NOTHROW AP_OpticalFlow_CXOF(_frontend, uart);
return sensor; return sensor;
} }

View File

@ -26,7 +26,7 @@
AP_OpticalFlow_MAV *AP_OpticalFlow_MAV::detect(AP_OpticalFlow &_frontend) AP_OpticalFlow_MAV *AP_OpticalFlow_MAV::detect(AP_OpticalFlow &_frontend)
{ {
// we assume mavlink messages will be sent into this driver // we assume mavlink messages will be sent into this driver
AP_OpticalFlow_MAV *sensor = new AP_OpticalFlow_MAV(_frontend); AP_OpticalFlow_MAV *sensor = NEW_NOTHROW AP_OpticalFlow_MAV(_frontend);
return sensor; return sensor;
} }

View File

@ -29,7 +29,7 @@ using namespace MSP;
AP_OpticalFlow_MSP *AP_OpticalFlow_MSP::detect(AP_OpticalFlow &_frontend) AP_OpticalFlow_MSP *AP_OpticalFlow_MSP::detect(AP_OpticalFlow &_frontend)
{ {
// we assume msp messages will be sent into this driver // we assume msp messages will be sent into this driver
return new AP_OpticalFlow_MSP(_frontend); return NEW_NOTHROW AP_OpticalFlow_MSP(_frontend);
} }
// read latest values from sensor and fill in x,y and totals. // read latest values from sensor and fill in x,y and totals.

View File

@ -40,7 +40,7 @@ extern const AP_HAL::HAL& hal;
// detect the device // detect the device
AP_OpticalFlow_PX4Flow *AP_OpticalFlow_PX4Flow::detect(AP_OpticalFlow &_frontend) AP_OpticalFlow_PX4Flow *AP_OpticalFlow_PX4Flow::detect(AP_OpticalFlow &_frontend)
{ {
AP_OpticalFlow_PX4Flow *sensor = new AP_OpticalFlow_PX4Flow(_frontend); AP_OpticalFlow_PX4Flow *sensor = NEW_NOTHROW AP_OpticalFlow_PX4Flow(_frontend);
if (!sensor) { if (!sensor) {
return nullptr; return nullptr;
} }

View File

@ -94,7 +94,7 @@ AP_OpticalFlow_Pixart::AP_OpticalFlow_Pixart(const char *devname, AP_OpticalFlow
// detect the device // detect the device
AP_OpticalFlow_Pixart *AP_OpticalFlow_Pixart::detect(const char *devname, AP_OpticalFlow &_frontend) AP_OpticalFlow_Pixart *AP_OpticalFlow_Pixart::detect(const char *devname, AP_OpticalFlow &_frontend)
{ {
AP_OpticalFlow_Pixart *sensor = new AP_OpticalFlow_Pixart(devname, _frontend); AP_OpticalFlow_Pixart *sensor = NEW_NOTHROW AP_OpticalFlow_Pixart(devname, _frontend);
if (!sensor) { if (!sensor) {
return nullptr; return nullptr;
} }

View File

@ -74,7 +74,7 @@ AP_OpticalFlow_UPFLOW *AP_OpticalFlow_UPFLOW::detect(AP_OpticalFlow &_frontend)
} }
// we have found a serial port so use it // we have found a serial port so use it
AP_OpticalFlow_UPFLOW *sensor = new AP_OpticalFlow_UPFLOW(_frontend, uart); AP_OpticalFlow_UPFLOW *sensor = NEW_NOTHROW AP_OpticalFlow_UPFLOW(_frontend, uart);
return sensor; return sensor;
} }