mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Empty: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
8dbad82c8a
commit
d3133b8fa1
|
@ -33,7 +33,7 @@ void AnalogIn::init()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) {
|
AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) {
|
||||||
return new AnalogSource(1.11);
|
return NEW_NOTHROW AnalogSource(1.11);
|
||||||
}
|
}
|
||||||
|
|
||||||
float AnalogIn::board_voltage(void)
|
float AnalogIn::board_voltage(void)
|
||||||
|
|
|
@ -24,7 +24,7 @@ void GPIO::toggle(uint8_t pin)
|
||||||
|
|
||||||
/* Alternative interface: */
|
/* Alternative interface: */
|
||||||
AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
|
AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
|
||||||
return new DigitalSource(0);
|
return NEW_NOTHROW DigitalSource(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool GPIO::usb_connected(void)
|
bool GPIO::usb_connected(void)
|
||||||
|
|
Loading…
Reference in New Issue