mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
f1c6538f34
commit
17e338d7f6
|
@ -69,7 +69,7 @@ void AnalogIn::init() {
|
|||
}
|
||||
|
||||
AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin) {
|
||||
return new ADCSource(_sitlState, pin);
|
||||
return NEW_NOTHROW ADCSource(_sitlState, pin);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -217,11 +217,11 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode)
|
|||
const SITL::SIM::CANTransport can_type = _sitl->can_transport[_self_index];
|
||||
switch (can_type) {
|
||||
case SITL::SIM::CANTransport::MulticastUDP:
|
||||
transport = new CAN_Multicast();
|
||||
transport = NEW_NOTHROW CAN_Multicast();
|
||||
break;
|
||||
case SITL::SIM::CANTransport::SocketCAN:
|
||||
#if HAL_CAN_WITH_SOCKETCAN
|
||||
transport = new CAN_SocketCAN();
|
||||
transport = NEW_NOTHROW CAN_SocketCAN();
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -39,7 +39,7 @@ extern const AP_HAL::HAL& hal;
|
|||
// initialize the FFT state machine
|
||||
AP_HAL::DSP::FFTWindowState* DSP::fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size)
|
||||
{
|
||||
DSP::FFTWindowStateSITL* fft = new DSP::FFTWindowStateSITL(window_size, sample_rate, sliding_window_size);
|
||||
DSP::FFTWindowStateSITL* fft = NEW_NOTHROW DSP::FFTWindowStateSITL(window_size, sample_rate, sliding_window_size);
|
||||
if (fft == nullptr || fft->_hanning_window == nullptr || fft->_rfft_data == nullptr || fft->_freq_bins == nullptr || fft->_derivative_freq_bins == nullptr) {
|
||||
delete fft;
|
||||
return nullptr;
|
||||
|
@ -71,7 +71,7 @@ DSP::FFTWindowStateSITL::FFTWindowStateSITL(uint16_t window_size, uint16_t sampl
|
|||
return;
|
||||
}
|
||||
|
||||
buf = new complexf[window_size];
|
||||
buf = NEW_NOTHROW complexf[window_size];
|
||||
}
|
||||
|
||||
DSP::FFTWindowStateSITL::~FFTWindowStateSITL()
|
||||
|
|
|
@ -82,7 +82,7 @@ void GPIO::toggle(uint8_t pin)
|
|||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
|
||||
if (n < 16) { // (ie. sizeof(pin_mask)*8)
|
||||
return new DigitalSource(static_cast<uint8_t>(n));
|
||||
return NEW_NOTHROW DigitalSource(static_cast<uint8_t>(n));
|
||||
} else {
|
||||
return nullptr;
|
||||
}
|
||||
|
|
|
@ -67,7 +67,7 @@ int I2CBus::_ioctl(uint8_t ioctl_number, void *data)
|
|||
AP_HAL::Device::PeriodicHandle I2CBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
|
||||
{
|
||||
// mostly swiped from ChibiOS:
|
||||
I2CBus::callback_info *callback = new I2CBus::callback_info;
|
||||
I2CBus::callback_info *callback = NEW_NOTHROW I2CBus::callback_info;
|
||||
if (callback == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -116,7 +116,7 @@ I2CDeviceManager::get_device(uint8_t bus,
|
|||
if (bus >= ARRAY_SIZE(buses)) {
|
||||
return AP_HAL::OwnPtr<AP_HAL::I2CDevice>(nullptr);
|
||||
}
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(buses[bus], address));
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(NEW_NOTHROW I2CDevice(buses[bus], address));
|
||||
return dev;
|
||||
}
|
||||
|
||||
|
|
|
@ -101,7 +101,7 @@ void RCOutput::push(void)
|
|||
SITL::SIM *sitl = AP::sitl();
|
||||
if (sitl && sitl->esc_telem) {
|
||||
if (esc_telem == nullptr) {
|
||||
esc_telem = new AP_ESC_Telem_SITL;
|
||||
esc_telem = NEW_NOTHROW AP_ESC_Telem_SITL;
|
||||
}
|
||||
if (esc_telem != nullptr) {
|
||||
esc_telem->update();
|
||||
|
|
|
@ -112,7 +112,7 @@ void SITL_State::init(int argc, char * const argv[]) {
|
|||
|
||||
printf("Running Instance: %d\n", _instance);
|
||||
|
||||
sitl_model = new SimMCast("");
|
||||
sitl_model = NEW_NOTHROW SimMCast("");
|
||||
|
||||
_sitl = AP::sitl();
|
||||
|
||||
|
|
|
@ -80,7 +80,7 @@ void SITL_State::_sitl_setup()
|
|||
// setup some initial values
|
||||
_update_airspeed(0);
|
||||
if (enable_gimbal) {
|
||||
gimbal = new SITL::Gimbal(_sitl->state);
|
||||
gimbal = NEW_NOTHROW SITL::Gimbal(_sitl->state);
|
||||
}
|
||||
|
||||
sitl_model->set_buzzer(&_sitl->buzzer_sim);
|
||||
|
|
|
@ -31,14 +31,14 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (benewake_tf02 != nullptr) {
|
||||
AP_HAL::panic("Only one benewake_tf02 at a time");
|
||||
}
|
||||
benewake_tf02 = new SITL::RF_Benewake_TF02();
|
||||
benewake_tf02 = NEW_NOTHROW SITL::RF_Benewake_TF02();
|
||||
return benewake_tf02;
|
||||
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||
} else if (streq(name, "vicon")) {
|
||||
if (vicon != nullptr) {
|
||||
AP_HAL::panic("Only one vicon system at a time");
|
||||
}
|
||||
vicon = new SITL::Vicon();
|
||||
vicon = NEW_NOTHROW SITL::Vicon();
|
||||
return vicon;
|
||||
#endif
|
||||
#if HAL_SIM_ADSB_ENABLED
|
||||
|
@ -47,7 +47,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
// will cope with begin() being called multiple times on a
|
||||
// serial port
|
||||
if (adsb == nullptr) {
|
||||
adsb = new SITL::ADSB();
|
||||
adsb = NEW_NOTHROW SITL::ADSB();
|
||||
}
|
||||
sitl_model->set_adsb(adsb);
|
||||
return adsb;
|
||||
|
@ -56,97 +56,97 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (ainsteinlrd1 != nullptr) {
|
||||
AP_HAL::panic("Only one ainsteinlrd1 at a time");
|
||||
}
|
||||
ainsteinlrd1 = new SITL::RF_Ainstein_LR_D1();
|
||||
ainsteinlrd1 = NEW_NOTHROW SITL::RF_Ainstein_LR_D1();
|
||||
return ainsteinlrd1;
|
||||
} else if (streq(name, "benewake_tf03")) {
|
||||
if (benewake_tf03 != nullptr) {
|
||||
AP_HAL::panic("Only one benewake_tf03 at a time");
|
||||
}
|
||||
benewake_tf03 = new SITL::RF_Benewake_TF03();
|
||||
benewake_tf03 = NEW_NOTHROW SITL::RF_Benewake_TF03();
|
||||
return benewake_tf03;
|
||||
} else if (streq(name, "benewake_tfmini")) {
|
||||
if (benewake_tfmini != nullptr) {
|
||||
AP_HAL::panic("Only one benewake_tfmini at a time");
|
||||
}
|
||||
benewake_tfmini = new SITL::RF_Benewake_TFmini();
|
||||
benewake_tfmini = NEW_NOTHROW SITL::RF_Benewake_TFmini();
|
||||
return benewake_tfmini;
|
||||
} else if (streq(name, "nooploop_tofsense")) {
|
||||
if (nooploop != nullptr) {
|
||||
AP_HAL::panic("Only one nooploop_tofsense at a time");
|
||||
}
|
||||
nooploop = new SITL::RF_Nooploop();
|
||||
nooploop = NEW_NOTHROW SITL::RF_Nooploop();
|
||||
return nooploop;
|
||||
} else if (streq(name, "teraranger_serial")) {
|
||||
if (teraranger_serial != nullptr) {
|
||||
AP_HAL::panic("Only one teraranger_serial at a time");
|
||||
}
|
||||
teraranger_serial = new SITL::RF_TeraRanger_Serial();
|
||||
teraranger_serial = NEW_NOTHROW SITL::RF_TeraRanger_Serial();
|
||||
return teraranger_serial;
|
||||
} else if (streq(name, "lightwareserial")) {
|
||||
if (lightwareserial != nullptr) {
|
||||
AP_HAL::panic("Only one lightwareserial at a time");
|
||||
}
|
||||
lightwareserial = new SITL::RF_LightWareSerial();
|
||||
lightwareserial = NEW_NOTHROW SITL::RF_LightWareSerial();
|
||||
return lightwareserial;
|
||||
} else if (streq(name, "lightwareserial-binary")) {
|
||||
if (lightwareserial_binary != nullptr) {
|
||||
AP_HAL::panic("Only one lightwareserial-binary at a time");
|
||||
}
|
||||
lightwareserial_binary = new SITL::RF_LightWareSerialBinary();
|
||||
lightwareserial_binary = NEW_NOTHROW SITL::RF_LightWareSerialBinary();
|
||||
return lightwareserial_binary;
|
||||
} else if (streq(name, "lanbao")) {
|
||||
if (lanbao != nullptr) {
|
||||
AP_HAL::panic("Only one lanbao at a time");
|
||||
}
|
||||
lanbao = new SITL::RF_Lanbao();
|
||||
lanbao = NEW_NOTHROW SITL::RF_Lanbao();
|
||||
return lanbao;
|
||||
} else if (streq(name, "blping")) {
|
||||
if (blping != nullptr) {
|
||||
AP_HAL::panic("Only one blping at a time");
|
||||
}
|
||||
blping = new SITL::RF_BLping();
|
||||
blping = NEW_NOTHROW SITL::RF_BLping();
|
||||
return blping;
|
||||
} else if (streq(name, "leddarone")) {
|
||||
if (leddarone != nullptr) {
|
||||
AP_HAL::panic("Only one leddarone at a time");
|
||||
}
|
||||
leddarone = new SITL::RF_LeddarOne();
|
||||
leddarone = NEW_NOTHROW SITL::RF_LeddarOne();
|
||||
return leddarone;
|
||||
} else if (streq(name, "rds02uf")) {
|
||||
if (rds02uf != nullptr) {
|
||||
AP_HAL::panic("Only one rds02uf at a time");
|
||||
}
|
||||
rds02uf = new SITL::RF_RDS02UF();
|
||||
rds02uf = NEW_NOTHROW SITL::RF_RDS02UF();
|
||||
return rds02uf;
|
||||
} else if (streq(name, "USD1_v0")) {
|
||||
if (USD1_v0 != nullptr) {
|
||||
AP_HAL::panic("Only one USD1_v0 at a time");
|
||||
}
|
||||
USD1_v0 = new SITL::RF_USD1_v0();
|
||||
USD1_v0 = NEW_NOTHROW SITL::RF_USD1_v0();
|
||||
return USD1_v0;
|
||||
} else if (streq(name, "USD1_v1")) {
|
||||
if (USD1_v1 != nullptr) {
|
||||
AP_HAL::panic("Only one USD1_v1 at a time");
|
||||
}
|
||||
USD1_v1 = new SITL::RF_USD1_v1();
|
||||
USD1_v1 = NEW_NOTHROW SITL::RF_USD1_v1();
|
||||
return USD1_v1;
|
||||
} else if (streq(name, "maxsonarseriallv")) {
|
||||
if (maxsonarseriallv != nullptr) {
|
||||
AP_HAL::panic("Only one maxsonarseriallv at a time");
|
||||
}
|
||||
maxsonarseriallv = new SITL::RF_MaxsonarSerialLV();
|
||||
maxsonarseriallv = NEW_NOTHROW SITL::RF_MaxsonarSerialLV();
|
||||
return maxsonarseriallv;
|
||||
} else if (streq(name, "wasp")) {
|
||||
if (wasp != nullptr) {
|
||||
AP_HAL::panic("Only one wasp at a time");
|
||||
}
|
||||
wasp = new SITL::RF_Wasp();
|
||||
wasp = NEW_NOTHROW SITL::RF_Wasp();
|
||||
return wasp;
|
||||
} else if (streq(name, "nmea")) {
|
||||
if (nmea != nullptr) {
|
||||
AP_HAL::panic("Only one nmea at a time");
|
||||
}
|
||||
nmea = new SITL::RF_NMEA();
|
||||
nmea = NEW_NOTHROW SITL::RF_NMEA();
|
||||
return nmea;
|
||||
|
||||
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||
|
@ -154,34 +154,34 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (rf_mavlink != nullptr) {
|
||||
AP_HAL::panic("Only one rf_mavlink at a time");
|
||||
}
|
||||
rf_mavlink = new SITL::RF_MAVLink();
|
||||
rf_mavlink = NEW_NOTHROW SITL::RF_MAVLink();
|
||||
return rf_mavlink;
|
||||
#endif
|
||||
} else if (streq(name, "frsky-d")) {
|
||||
if (frsky_d != nullptr) {
|
||||
AP_HAL::panic("Only one frsky_d at a time");
|
||||
}
|
||||
frsky_d = new SITL::Frsky_D();
|
||||
frsky_d = NEW_NOTHROW SITL::Frsky_D();
|
||||
return frsky_d;
|
||||
// } else if (streq(name, "frsky-SPort")) {
|
||||
// if (frsky_sport != nullptr) {
|
||||
// AP_HAL::panic("Only one frsky_sport at a time");
|
||||
// }
|
||||
// frsky_sport = new SITL::Frsky_SPort();
|
||||
// frsky_sport = NEW_NOTHROW SITL::Frsky_SPort();
|
||||
// return frsky_sport;
|
||||
|
||||
// } else if (streq(name, "frsky-SPortPassthrough")) {
|
||||
// if (frsky_sport_passthrough != nullptr) {
|
||||
// AP_HAL::panic("Only one frsky_sport passthrough at a time");
|
||||
// }
|
||||
// frsky_sport = new SITL::Frsky_SPortPassthrough();
|
||||
// frsky_sport = NEW_NOTHROW SITL::Frsky_SPortPassthrough();
|
||||
// return frsky_sportpassthrough;
|
||||
#if AP_SIM_CRSF_ENABLED
|
||||
} else if (streq(name, "crsf")) {
|
||||
if (crsf != nullptr) {
|
||||
AP_HAL::panic("Only one crsf at a time");
|
||||
}
|
||||
crsf = new SITL::CRSF();
|
||||
crsf = NEW_NOTHROW SITL::CRSF();
|
||||
return crsf;
|
||||
#endif
|
||||
#if HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
|
@ -189,7 +189,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (rplidara2 != nullptr) {
|
||||
AP_HAL::panic("Only one rplidara2 at a time");
|
||||
}
|
||||
rplidara2 = new SITL::PS_RPLidarA2();
|
||||
rplidara2 = NEW_NOTHROW SITL::PS_RPLidarA2();
|
||||
return rplidara2;
|
||||
#endif
|
||||
#if HAL_SIM_PS_RPLIDARA1_ENABLED
|
||||
|
@ -197,7 +197,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (rplidara1 != nullptr) {
|
||||
AP_HAL::panic("Only one rplidara1 at a time");
|
||||
}
|
||||
rplidara1 = new SITL::PS_RPLidarA1();
|
||||
rplidara1 = NEW_NOTHROW SITL::PS_RPLidarA1();
|
||||
return rplidara1;
|
||||
#endif
|
||||
#if HAL_SIM_PS_TERARANGERTOWER_ENABLED
|
||||
|
@ -205,7 +205,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (terarangertower != nullptr) {
|
||||
AP_HAL::panic("Only one terarangertower at a time");
|
||||
}
|
||||
terarangertower = new SITL::PS_TeraRangerTower();
|
||||
terarangertower = NEW_NOTHROW SITL::PS_TeraRangerTower();
|
||||
return terarangertower;
|
||||
#endif
|
||||
#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED
|
||||
|
@ -213,7 +213,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (sf45b != nullptr) {
|
||||
AP_HAL::panic("Only one sf45b at a time");
|
||||
}
|
||||
sf45b = new SITL::PS_LightWare_SF45B();
|
||||
sf45b = NEW_NOTHROW SITL::PS_LightWare_SF45B();
|
||||
return sf45b;
|
||||
#endif
|
||||
#if AP_SIM_ADSB_SAGETECH_MXS_ENABLED
|
||||
|
@ -221,9 +221,9 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (sagetech_mxs != nullptr) {
|
||||
AP_HAL::panic("Only one sagetech_mxs at a time");
|
||||
}
|
||||
sagetech_mxs = new SITL::ADSB_Sagetech_MXS();
|
||||
sagetech_mxs = NEW_NOTHROW SITL::ADSB_Sagetech_MXS();
|
||||
if (adsb == nullptr) {
|
||||
adsb = new SITL::ADSB();
|
||||
adsb = NEW_NOTHROW SITL::ADSB();
|
||||
}
|
||||
sitl_model->set_adsb(adsb);
|
||||
return sagetech_mxs;
|
||||
|
@ -248,51 +248,51 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (jre != nullptr) {
|
||||
AP_HAL::panic("Only one jre at a time");
|
||||
}
|
||||
jre = new SITL::RF_JRE();
|
||||
jre = NEW_NOTHROW SITL::RF_JRE();
|
||||
return jre;
|
||||
} else if (streq(name, "gyus42v2")) {
|
||||
if (gyus42v2 != nullptr) {
|
||||
AP_HAL::panic("Only one gyus42v2 at a time");
|
||||
}
|
||||
gyus42v2 = new SITL::RF_GYUS42v2();
|
||||
gyus42v2 = NEW_NOTHROW SITL::RF_GYUS42v2();
|
||||
return gyus42v2;
|
||||
} else if (streq(name, "megasquirt")) {
|
||||
if (efi_ms != nullptr) {
|
||||
AP_HAL::panic("Only one megasquirt at a time");
|
||||
}
|
||||
efi_ms = new SITL::EFI_MegaSquirt();
|
||||
efi_ms = NEW_NOTHROW SITL::EFI_MegaSquirt();
|
||||
return efi_ms;
|
||||
} else if (streq(name, "hirth")) {
|
||||
if (efi_hirth != nullptr) {
|
||||
AP_HAL::panic("Only one hirth at a time");
|
||||
}
|
||||
efi_hirth = new SITL::EFI_Hirth();
|
||||
efi_hirth = NEW_NOTHROW SITL::EFI_Hirth();
|
||||
return efi_hirth;
|
||||
} else if (streq(name, "VectorNav")) {
|
||||
if (vectornav != nullptr) {
|
||||
AP_HAL::panic("Only one VectorNav at a time");
|
||||
}
|
||||
vectornav = new SITL::VectorNav();
|
||||
vectornav = NEW_NOTHROW SITL::VectorNav();
|
||||
return vectornav;
|
||||
} else if (streq(name, "MicroStrain5")) {
|
||||
if (microstrain5 != nullptr) {
|
||||
AP_HAL::panic("Only one MicroStrain5 at a time");
|
||||
}
|
||||
microstrain5 = new SITL::MicroStrain5();
|
||||
microstrain5 = NEW_NOTHROW SITL::MicroStrain5();
|
||||
return microstrain5;
|
||||
|
||||
} else if (streq(name, "MicroStrain7")) {
|
||||
if (microstrain7 != nullptr) {
|
||||
AP_HAL::panic("Only one MicroStrain7 at a time");
|
||||
}
|
||||
microstrain7 = new SITL::MicroStrain7();
|
||||
microstrain7 = NEW_NOTHROW SITL::MicroStrain7();
|
||||
return microstrain7;
|
||||
|
||||
} else if (streq(name, "ILabs")) {
|
||||
if (inertiallabs != nullptr) {
|
||||
AP_HAL::panic("Only one InertialLabs INS at a time");
|
||||
}
|
||||
inertiallabs = new SITL::InertialLabs();
|
||||
inertiallabs = NEW_NOTHROW SITL::InertialLabs();
|
||||
return inertiallabs;
|
||||
|
||||
#if HAL_SIM_AIS_ENABLED
|
||||
|
@ -300,7 +300,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (ais != nullptr) {
|
||||
AP_HAL::panic("Only one AIS at a time");
|
||||
}
|
||||
ais = new SITL::AIS();
|
||||
ais = NEW_NOTHROW SITL::AIS();
|
||||
return ais;
|
||||
#endif
|
||||
} else if (strncmp(name, "gps", 3) == 0) {
|
||||
|
@ -312,13 +312,13 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||
if (x <= 0 || x > ARRAY_SIZE(gps)) {
|
||||
AP_HAL::panic("Bad GPS number %u", x);
|
||||
}
|
||||
gps[x-1] = new SITL::GPS(x-1);
|
||||
gps[x-1] = NEW_NOTHROW SITL::GPS(x-1);
|
||||
return gps[x-1];
|
||||
} else if (streq(name, "ELRS")) {
|
||||
// Only allocate if not done already
|
||||
// MAVLink serial ports have begin called several times
|
||||
if (elrs == nullptr) {
|
||||
elrs = new SITL::ELRS(portNumber, this);
|
||||
elrs = NEW_NOTHROW SITL::ELRS(portNumber, this);
|
||||
_sitl->set_stop_MAVLink_sim_state();
|
||||
}
|
||||
return elrs;
|
||||
|
|
|
@ -73,7 +73,7 @@ int SPIBus::_ioctl(uint8_t cs_pin, uint8_t ioctl_number, void *data)
|
|||
AP_HAL::Device::PeriodicHandle SPIBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
|
||||
{
|
||||
// mostly swiped from ChibiOS:
|
||||
SPIBus::callback_info *callback = new SPIBus::callback_info;
|
||||
SPIBus::callback_info *callback = NEW_NOTHROW SPIBus::callback_info;
|
||||
if (callback == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -150,7 +150,7 @@ SPIDeviceManager::get_device(const char *name)
|
|||
}
|
||||
if (busp == nullptr) {
|
||||
// create a new one
|
||||
busp = new SPIBus(desc.bus);
|
||||
busp = NEW_NOTHROW SPIBus(desc.bus);
|
||||
if (busp == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -160,7 +160,7 @@ SPIDeviceManager::get_device(const char *name)
|
|||
buses = busp;
|
||||
}
|
||||
|
||||
return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(*busp, desc));
|
||||
return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(NEW_NOTHROW SPIDevice(*busp, desc));
|
||||
}
|
||||
|
||||
// void SPIDeviceManager::_timer_tick()
|
||||
|
|
|
@ -351,7 +351,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
|||
pthread_t thread {};
|
||||
const uint32_t alloc_stack = MAX(size_t(PTHREAD_STACK_MIN),stack_size);
|
||||
|
||||
struct thread_attr *a = new struct thread_attr;
|
||||
struct thread_attr *a = NEW_NOTHROW struct thread_attr;
|
||||
if (!a) {
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue