mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
20959524b8
commit
f1c6538f34
|
@ -44,7 +44,7 @@ extern const AP_HAL::HAL &hal;
|
|||
|
||||
AnalogIn_ADS1115::AnalogIn_ADS1115()
|
||||
{
|
||||
_adc = new AP_ADC_ADS1115();
|
||||
_adc = NEW_NOTHROW AP_ADC_ADS1115();
|
||||
_channels_number = _adc->get_channels_number();
|
||||
}
|
||||
|
||||
|
@ -53,7 +53,7 @@ AP_HAL::AnalogSource* AnalogIn_ADS1115::channel(int16_t pin)
|
|||
WITH_SEMAPHORE(_semaphore);
|
||||
for (uint8_t j = 0; j < _channels_number; j++) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new AnalogSource_ADS1115(pin);
|
||||
_channels[j] = NEW_NOTHROW AnalogSource_ADS1115(pin);
|
||||
return _channels[j];
|
||||
}
|
||||
}
|
||||
|
|
|
@ -129,5 +129,5 @@ void AnalogIn_IIO::init()
|
|||
|
||||
|
||||
AP_HAL::AnalogSource* AnalogIn_IIO::channel(int16_t pin) {
|
||||
return new AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING);
|
||||
return NEW_NOTHROW AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING);
|
||||
}
|
||||
|
|
|
@ -111,7 +111,7 @@ AP_HAL::AnalogSource *AnalogIn_Navio2::channel(int16_t pin)
|
|||
WITH_SEMAPHORE(_semaphore);
|
||||
for (uint8_t j = 0; j < _channels_number; j++) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new AnalogSource_Navio2(pin);
|
||||
_channels[j] = NEW_NOTHROW AnalogSource_Navio2(pin);
|
||||
return _channels[j];
|
||||
}
|
||||
}
|
||||
|
|
|
@ -114,7 +114,7 @@ void GPIO_BBB::toggle(uint8_t pin)
|
|||
|
||||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* GPIO_BBB::channel(uint16_t n) {
|
||||
return new DigitalSource(n);
|
||||
return NEW_NOTHROW DigitalSource(n);
|
||||
}
|
||||
|
||||
bool GPIO_BBB::usb_connected(void)
|
||||
|
|
|
@ -30,11 +30,11 @@ void GPIO_RPI::init()
|
|||
case LINUX_BOARD_TYPE::RPI_ZERO_1:
|
||||
case LINUX_BOARD_TYPE::RPI_2_3_ZERO2:
|
||||
case LINUX_BOARD_TYPE::RPI_4:
|
||||
gpioDriver = new GPIO_RPI_BCM();
|
||||
gpioDriver = NEW_NOTHROW GPIO_RPI_BCM();
|
||||
gpioDriver->init();
|
||||
break;
|
||||
case LINUX_BOARD_TYPE::RPI_5:
|
||||
gpioDriver = new GPIO_RPI_RP1();
|
||||
gpioDriver = NEW_NOTHROW GPIO_RPI_RP1();
|
||||
gpioDriver->init();
|
||||
break;
|
||||
default:
|
||||
|
@ -71,7 +71,7 @@ void GPIO_RPI::toggle(uint8_t pin)
|
|||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* GPIO_RPI::channel(uint16_t n)
|
||||
{
|
||||
return new DigitalSource(n);
|
||||
return NEW_NOTHROW DigitalSource(n);
|
||||
}
|
||||
|
||||
bool GPIO_RPI::usb_connected(void)
|
||||
|
|
|
@ -232,7 +232,7 @@ void GPIO_RPI_BCM::toggle(uint8_t pin)
|
|||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* GPIO_RPI_BCM::channel(uint16_t n)
|
||||
{
|
||||
return new DigitalSource(n);
|
||||
return NEW_NOTHROW DigitalSource(n);
|
||||
}
|
||||
|
||||
bool GPIO_RPI_BCM::usb_connected(void)
|
||||
|
|
|
@ -205,7 +205,7 @@ AP_HAL::DigitalSource* GPIO_Sysfs::channel(uint16_t vpin)
|
|||
/* Even if we couldn't open the fd, return a new DigitalSource and let
|
||||
* reads and writes fail later due to invalid. Otherwise we
|
||||
* could crash in undesired places */
|
||||
return new DigitalSource_Sysfs(pin, value_fd);
|
||||
return NEW_NOTHROW DigitalSource_Sysfs(pin, value_fd);
|
||||
}
|
||||
|
||||
bool GPIO_Sysfs::usb_connected(void)
|
||||
|
|
|
@ -165,7 +165,7 @@ static RCInput_PRU rcinDriver;
|
|||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
|
||||
static RCInput_AioPRU rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
|
||||
static RCInput_Multi rcinDriver{2, new RCInput_AioPRU, new RCInput_RCProtocol(NULL, "/dev/ttyO4")};
|
||||
static RCInput_Multi rcinDriver{2, NEW_NOTHROW RCInput_AioPRU, NEW_NOTHROW RCInput_RCProtocol(NULL, "/dev/ttyO4")};
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
|
||||
|
@ -180,7 +180,7 @@ static RCInput_ZYNQ rcinDriver;
|
|||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
static RCInput_UDP rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
static RCInput_Multi rcinDriver{2, new RCInput_RCProtocol("/dev/uart-sbus", "/dev/uart-sumd"), new RCInput_UDP()};
|
||||
static RCInput_Multi rcinDriver{2, NEW_NOTHROW RCInput_RCProtocol("/dev/uart-sbus", "/dev/uart-sumd"), NEW_NOTHROW RCInput_UDP()};
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
static RCInput_SoloLink rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \
|
||||
|
|
|
@ -42,11 +42,11 @@ HeatPwm::HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns) :
|
|||
_period_ns(period_ns)
|
||||
{
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
|
||||
_pwm = new PWM_Sysfs(0, pwm_num);
|
||||
_pwm = NEW_NOTHROW PWM_Sysfs(0, pwm_num);
|
||||
hal.gpio->pinMode(EDGE_GPIO_HEAT_ENABLE, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(EDGE_GPIO_HEAT_ENABLE, 1);
|
||||
#else
|
||||
_pwm = new PWM_Sysfs_Bebop(pwm_num);
|
||||
_pwm = NEW_NOTHROW PWM_Sysfs_Bebop(pwm_num);
|
||||
#endif
|
||||
_pwm->init();
|
||||
_pwm->set_period(_period_ns);
|
||||
|
|
|
@ -377,7 +377,7 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
|
|||
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
||||
I2CDeviceManager::_create_device(I2CBus &b, uint8_t address) const
|
||||
{
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(b, address));
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(NEW_NOTHROW I2CDevice(b, address));
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
|
|
|
@ -55,7 +55,7 @@ void OpticalFlow_Onboard::init()
|
|||
return;
|
||||
}
|
||||
|
||||
_videoin = new VideoIn;
|
||||
_videoin = NEW_NOTHROW VideoIn;
|
||||
const char* device_path = HAL_OPTFLOW_ONBOARD_VDEV_PATH;
|
||||
memtype = V4L2_MEMORY_MMAP;
|
||||
nbufs = HAL_OPTFLOW_ONBOARD_NBUFS;
|
||||
|
@ -75,12 +75,12 @@ void OpticalFlow_Onboard::init()
|
|||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
_pwm = new PWM_Sysfs_Bebop(BEBOP_CAMV_PWM);
|
||||
_pwm = NEW_NOTHROW PWM_Sysfs_Bebop(BEBOP_CAMV_PWM);
|
||||
_pwm->init();
|
||||
_pwm->set_freq(BEBOP_CAMV_PWM_FREQ);
|
||||
_pwm->enable(true);
|
||||
|
||||
_camerasensor = new CameraSensor_Mt9v117(HAL_OPTFLOW_ONBOARD_SUBDEV_PATH,
|
||||
_camerasensor = NEW_NOTHROW CameraSensor_Mt9v117(HAL_OPTFLOW_ONBOARD_SUBDEV_PATH,
|
||||
hal.i2c_mgr->get_device(0, 0x5D),
|
||||
MT9V117_QVGA,
|
||||
BEBOP_GPIO_CAMV_NRST,
|
||||
|
@ -146,7 +146,7 @@ void OpticalFlow_Onboard::init()
|
|||
_videoin->prepare_capture();
|
||||
|
||||
/* Use px4 algorithm for optical flow */
|
||||
_flow = new Flow_PX4(_width, _bytesperline,
|
||||
_flow = NEW_NOTHROW Flow_PX4(_width, _bytesperline,
|
||||
HAL_FLOW_PX4_MAX_FLOW_PIXEL,
|
||||
HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD,
|
||||
HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD);
|
||||
|
@ -170,7 +170,7 @@ void OpticalFlow_Onboard::init()
|
|||
AP_HAL::panic("OpticalFlow_Onboard: failed to create thread");
|
||||
}
|
||||
|
||||
_gyro_ring_buffer = new ObjectBuffer<GyroSample>(OPTICAL_FLOW_GYRO_BUFFER_LEN);
|
||||
_gyro_ring_buffer = NEW_NOTHROW ObjectBuffer<GyroSample>(OPTICAL_FLOW_GYRO_BUFFER_LEN);
|
||||
if (_gyro_ring_buffer != nullptr && _gyro_ring_buffer->get_size() == 0) {
|
||||
// allocation failed
|
||||
delete _gyro_ring_buffer;
|
||||
|
|
|
@ -93,7 +93,7 @@ TimerPollable *PollerThread::add_timer(TimerPollable::PeriodicCb cb,
|
|||
if (!_poller) {
|
||||
return nullptr;
|
||||
}
|
||||
TimerPollable *p = new TimerPollable(cb, wrapper);
|
||||
TimerPollable *p = NEW_NOTHROW TimerPollable(cb, wrapper);
|
||||
if (!p || !p->setup_timer(timeout_usec) ||
|
||||
!_poller.register_pollable(p, POLLIN)) {
|
||||
delete p;
|
||||
|
|
|
@ -31,7 +31,7 @@ RCInput_Multi::RCInput_Multi(uint8_t _num_inputs, ...) :
|
|||
num_inputs(_num_inputs)
|
||||
{
|
||||
va_list ap;
|
||||
inputs = new RCInput*[num_inputs];
|
||||
inputs = NEW_NOTHROW RCInput*[num_inputs];
|
||||
if (inputs == nullptr) {
|
||||
AP_HAL::panic("failed to allocated RCInput array");
|
||||
}
|
||||
|
|
|
@ -534,8 +534,8 @@ void RCInput_RPI::init()
|
|||
set_physical_addresses();
|
||||
// Init memory for buffer and for DMA control blocks.
|
||||
// See comments in "init_ctrl_data()" to understand values "2" and "15"
|
||||
circle_buffer = new Memory_table(RCIN_RPI_BUFFER_LENGTH * 2, _version);
|
||||
con_blocks = new Memory_table(RCIN_RPI_BUFFER_LENGTH * 15, _version);
|
||||
circle_buffer = NEW_NOTHROW Memory_table(RCIN_RPI_BUFFER_LENGTH * 2, _version);
|
||||
con_blocks = NEW_NOTHROW Memory_table(RCIN_RPI_BUFFER_LENGTH * 15, _version);
|
||||
|
||||
init_registers();
|
||||
|
||||
|
|
|
@ -94,8 +94,8 @@ using namespace Linux;
|
|||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
RCOutput_AeroIO::RCOutput_AeroIO()
|
||||
: _freq_buffer(new uint16_t[PWM_CHAN_COUNT])
|
||||
, _duty_buffer(new uint16_t[PWM_CHAN_COUNT])
|
||||
: _freq_buffer(NEW_NOTHROW uint16_t[PWM_CHAN_COUNT])
|
||||
, _duty_buffer(NEW_NOTHROW uint16_t[PWM_CHAN_COUNT])
|
||||
{
|
||||
}
|
||||
|
||||
|
|
|
@ -65,7 +65,7 @@ RCOutput_PCA9685::RCOutput_PCA9685(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
|||
_dev(std::move(dev)),
|
||||
_enable_pin(nullptr),
|
||||
_frequency(50),
|
||||
_pulses_buffer(new uint16_t[PWM_CHAN_COUNT - channel_offset]),
|
||||
_pulses_buffer(NEW_NOTHROW uint16_t[PWM_CHAN_COUNT - channel_offset]),
|
||||
_external_clock(external_clock),
|
||||
_channel_offset(channel_offset),
|
||||
_oe_pin_number(oe_pin_number)
|
||||
|
|
|
@ -25,8 +25,8 @@ RCOutput_Sysfs::RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t chann
|
|||
: _chip(chip)
|
||||
, _channel_base(channel_base)
|
||||
, _channel_count(channel_count)
|
||||
, _pwm_channels(new PWM_Sysfs_Base *[_channel_count])
|
||||
, _pending(new uint16_t[_channel_count])
|
||||
, _pwm_channels(NEW_NOTHROW PWM_Sysfs_Base *[_channel_count])
|
||||
, _pending(NEW_NOTHROW uint16_t[_channel_count])
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -43,11 +43,11 @@ void RCOutput_Sysfs::init()
|
|||
{
|
||||
for (uint8_t i = 0; i < _channel_count; i++) {
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
_pwm_channels[i] = new PWM_Sysfs_Bebop(_channel_base+i);
|
||||
_pwm_channels[i] = NEW_NOTHROW PWM_Sysfs_Bebop(_channel_base+i);
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ
|
||||
_pwm_channels[i] = new PWM_Sysfs(_chip+i, 0);
|
||||
_pwm_channels[i] = NEW_NOTHROW PWM_Sysfs(_chip+i, 0);
|
||||
#else
|
||||
_pwm_channels[i] = new PWM_Sysfs(_chip, _channel_base+i);
|
||||
_pwm_channels[i] = NEW_NOTHROW PWM_Sysfs(_chip, _channel_base+i);
|
||||
#endif
|
||||
if (!_pwm_channels[i]) {
|
||||
AP_HAL::panic("RCOutput_Sysfs_PWM: Unable to setup PWM pin.");
|
||||
|
|
|
@ -503,7 +503,7 @@ SPIDeviceManager::_create_device(SPIBus &b, SPIDesc &desc) const
|
|||
// Ensure bus is open
|
||||
b.open(desc.subdev);
|
||||
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(b, desc));
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::SPIDevice>(NEW_NOTHROW SPIDevice(b, desc));
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
|
|
|
@ -54,7 +54,7 @@ void SPIUARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||
|
||||
if (_buffer == nullptr) {
|
||||
/* Do not allocate new buffer, if we're just changing speed */
|
||||
_buffer = new uint8_t[rxS];
|
||||
_buffer = NEW_NOTHROW uint8_t[rxS];
|
||||
if (_buffer == nullptr) {
|
||||
hal.console->printf("Not enough memory\n");
|
||||
AP_HAL::panic("Not enough memory\n");
|
||||
|
|
|
@ -408,7 +408,7 @@ uint8_t Scheduler::calculate_thread_priority(priority_base base, int8_t priority
|
|||
*/
|
||||
bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority)
|
||||
{
|
||||
Thread *thread = new Thread{(Thread::task_t)proc};
|
||||
Thread *thread = NEW_NOTHROW Thread{(Thread::task_t)proc};
|
||||
if (!thread) {
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -53,7 +53,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||
{
|
||||
if (!_initialised) {
|
||||
if (device_path == nullptr && _console) {
|
||||
_device = new ConsoleDevice();
|
||||
_device = NEW_NOTHROW ConsoleDevice();
|
||||
} else {
|
||||
if (device_path == nullptr) {
|
||||
return;
|
||||
|
@ -64,7 +64,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||
if (!_device.get()) {
|
||||
::fprintf(stderr, "Argument is not valid. Fallback to console.\n"
|
||||
"Launch with --help to see an example.\n");
|
||||
_device = new ConsoleDevice();
|
||||
_device = NEW_NOTHROW ConsoleDevice();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -133,7 +133,7 @@ AP_HAL::OwnPtr<SerialDevice> UARTDriver::_parseDevicePath(const char *arg)
|
|||
struct stat st;
|
||||
|
||||
if (stat(arg, &st) == 0 && S_ISCHR(st.st_mode)) {
|
||||
return AP_HAL::OwnPtr<SerialDevice>(new UARTDevice(arg));
|
||||
return AP_HAL::OwnPtr<SerialDevice>(NEW_NOTHROW UARTDevice(arg));
|
||||
} else if (strncmp(arg, "tcp:", 4) != 0 &&
|
||||
strncmp(arg, "udp:", 4) != 0 &&
|
||||
strncmp(arg, "udpin:", 6)) {
|
||||
|
@ -185,17 +185,17 @@ AP_HAL::OwnPtr<SerialDevice> UARTDriver::_parseDevicePath(const char *arg)
|
|||
_packetise = true;
|
||||
#endif
|
||||
if (strcmp(protocol, "udp") == 0) {
|
||||
device = new UDPDevice(_ip, _base_port, bcast, false);
|
||||
device = NEW_NOTHROW UDPDevice(_ip, _base_port, bcast, false);
|
||||
} else {
|
||||
if (bcast) {
|
||||
AP_HAL::panic("Can't combine udpin with bcast");
|
||||
}
|
||||
device = new UDPDevice(_ip, _base_port, false, true);
|
||||
device = NEW_NOTHROW UDPDevice(_ip, _base_port, false, true);
|
||||
|
||||
}
|
||||
} else {
|
||||
bool wait = (_flag && strcmp(_flag, "wait") == 0);
|
||||
device = new TCPServerDevice(_ip, _base_port, wait);
|
||||
device = NEW_NOTHROW TCPServerDevice(_ip, _base_port, wait);
|
||||
}
|
||||
|
||||
free(devstr);
|
||||
|
|
|
@ -29,7 +29,7 @@ void Util::init(int argc, char * const *argv) {
|
|||
|
||||
#ifdef HAL_UTILS_HEAT
|
||||
#if HAL_UTILS_HEAT == HAL_LINUX_HEAT_PWM
|
||||
_heat = new Linux::HeatPwm(HAL_LINUX_HEAT_PWM_NUM,
|
||||
_heat = NEW_NOTHROW Linux::HeatPwm(HAL_LINUX_HEAT_PWM_NUM,
|
||||
HAL_LINUX_HEAT_KP,
|
||||
HAL_LINUX_HEAT_KI,
|
||||
HAL_LINUX_HEAT_PERIOD_NS);
|
||||
|
@ -37,7 +37,7 @@ void Util::init(int argc, char * const *argv) {
|
|||
#error Unrecognized Heat
|
||||
#endif // #if
|
||||
#else
|
||||
_heat = new Linux::Heat();
|
||||
_heat = NEW_NOTHROW Linux::Heat();
|
||||
#endif // #ifdef
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue