mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
98caad29f5
commit
50253834ef
|
@ -136,27 +136,27 @@ void AP_DAL::init_sensors(void)
|
|||
|
||||
auto *rng = AP::rangefinder();
|
||||
if (rng && rng->num_sensors() > 0) {
|
||||
alloc_failed |= (_rangefinder = new AP_DAL_RangeFinder) == nullptr;
|
||||
alloc_failed |= (_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder) == nullptr;
|
||||
}
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
auto *aspeed = AP::airspeed();
|
||||
if (aspeed != nullptr && aspeed->get_num_sensors() > 0) {
|
||||
alloc_failed |= (_airspeed = new AP_DAL_Airspeed) == nullptr;
|
||||
alloc_failed |= (_airspeed = NEW_NOTHROW AP_DAL_Airspeed) == nullptr;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_BEACON_ENABLED
|
||||
auto *bcn = AP::beacon();
|
||||
if (bcn != nullptr && bcn->enabled()) {
|
||||
alloc_failed |= (_beacon = new AP_DAL_Beacon) == nullptr;
|
||||
alloc_failed |= (_beacon = NEW_NOTHROW AP_DAL_Beacon) == nullptr;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
auto *vodom = AP::visualodom();
|
||||
if (vodom != nullptr && vodom->enabled()) {
|
||||
alloc_failed |= (_visualodom = new AP_DAL_VisualOdom) == nullptr;
|
||||
alloc_failed |= (_visualodom = NEW_NOTHROW AP_DAL_VisualOdom) == nullptr;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -65,7 +65,7 @@ public:
|
|||
|
||||
static AP_DAL *get_singleton() {
|
||||
if (!_singleton) {
|
||||
_singleton = new AP_DAL();
|
||||
_singleton = NEW_NOTHROW AP_DAL();
|
||||
}
|
||||
return _singleton;
|
||||
}
|
||||
|
@ -242,13 +242,13 @@ public:
|
|||
|
||||
void handle_message(const log_RASH &msg) {
|
||||
if (_airspeed == nullptr) {
|
||||
_airspeed = new AP_DAL_Airspeed;
|
||||
_airspeed = NEW_NOTHROW AP_DAL_Airspeed;
|
||||
}
|
||||
_airspeed->handle_message(msg);
|
||||
}
|
||||
void handle_message(const log_RASI &msg) {
|
||||
if (_airspeed == nullptr) {
|
||||
_airspeed = new AP_DAL_Airspeed;
|
||||
_airspeed = NEW_NOTHROW AP_DAL_Airspeed;
|
||||
}
|
||||
_airspeed->handle_message(msg);
|
||||
}
|
||||
|
@ -262,13 +262,13 @@ public:
|
|||
|
||||
void handle_message(const log_RRNH &msg) {
|
||||
if (_rangefinder == nullptr) {
|
||||
_rangefinder = new AP_DAL_RangeFinder;
|
||||
_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder;
|
||||
}
|
||||
_rangefinder->handle_message(msg);
|
||||
}
|
||||
void handle_message(const log_RRNI &msg) {
|
||||
if (_rangefinder == nullptr) {
|
||||
_rangefinder = new AP_DAL_RangeFinder;
|
||||
_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder;
|
||||
}
|
||||
_rangefinder->handle_message(msg);
|
||||
}
|
||||
|
@ -293,7 +293,7 @@ public:
|
|||
void handle_message(const log_RBCH &msg) {
|
||||
#if AP_BEACON_ENABLED
|
||||
if (_beacon == nullptr) {
|
||||
_beacon = new AP_DAL_Beacon;
|
||||
_beacon = NEW_NOTHROW AP_DAL_Beacon;
|
||||
}
|
||||
_beacon->handle_message(msg);
|
||||
#endif
|
||||
|
@ -301,7 +301,7 @@ public:
|
|||
void handle_message(const log_RBCI &msg) {
|
||||
#if AP_BEACON_ENABLED
|
||||
if (_beacon == nullptr) {
|
||||
_beacon = new AP_DAL_Beacon;
|
||||
_beacon = NEW_NOTHROW AP_DAL_Beacon;
|
||||
}
|
||||
_beacon->handle_message(msg);
|
||||
#endif
|
||||
|
@ -309,7 +309,7 @@ public:
|
|||
void handle_message(const log_RVOH &msg) {
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
if (_visualodom == nullptr) {
|
||||
_visualodom = new AP_DAL_VisualOdom;
|
||||
_visualodom = NEW_NOTHROW AP_DAL_VisualOdom;
|
||||
}
|
||||
_visualodom->handle_message(msg);
|
||||
#endif
|
||||
|
|
|
@ -12,8 +12,8 @@ AP_DAL_RangeFinder::AP_DAL_RangeFinder()
|
|||
{
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
_RRNH.num_sensors = AP::rangefinder()->num_sensors();
|
||||
_RRNI = new log_RRNI[_RRNH.num_sensors];
|
||||
_backend = new AP_DAL_RangeFinder_Backend *[_RRNH.num_sensors];
|
||||
_RRNI = NEW_NOTHROW log_RRNI[_RRNH.num_sensors];
|
||||
_backend = NEW_NOTHROW AP_DAL_RangeFinder_Backend *[_RRNH.num_sensors];
|
||||
if (!_RRNI || !_backend) {
|
||||
goto failed;
|
||||
}
|
||||
|
@ -22,7 +22,7 @@ AP_DAL_RangeFinder::AP_DAL_RangeFinder()
|
|||
}
|
||||
for (uint8_t i=0; i<_RRNH.num_sensors; i++) {
|
||||
// this avoids having to discard a const....
|
||||
_backend[i] = new AP_DAL_RangeFinder_Backend(_RRNI[i]);
|
||||
_backend[i] = NEW_NOTHROW AP_DAL_RangeFinder_Backend(_RRNI[i]);
|
||||
if (!_backend[i]) {
|
||||
goto failed;
|
||||
}
|
||||
|
@ -132,8 +132,8 @@ void AP_DAL_RangeFinder::handle_message(const log_RRNH &msg)
|
|||
{
|
||||
_RRNH = msg;
|
||||
if (_RRNH.num_sensors > 0 && _RRNI == nullptr) {
|
||||
_RRNI = new log_RRNI[_RRNH.num_sensors];
|
||||
_backend = new AP_DAL_RangeFinder_Backend *[_RRNH.num_sensors];
|
||||
_RRNI = NEW_NOTHROW log_RRNI[_RRNH.num_sensors];
|
||||
_backend = NEW_NOTHROW AP_DAL_RangeFinder_Backend *[_RRNH.num_sensors];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -142,7 +142,7 @@ void AP_DAL_RangeFinder::handle_message(const log_RRNI &msg)
|
|||
if (_RRNI != nullptr && msg.instance < _RRNH.num_sensors) {
|
||||
_RRNI[msg.instance] = msg;
|
||||
if (_backend != nullptr && _backend[msg.instance] == nullptr) {
|
||||
_backend[msg.instance] = new AP_DAL_RangeFinder_Backend(_RRNI[msg.instance]);
|
||||
_backend[msg.instance] = NEW_NOTHROW AP_DAL_RangeFinder_Backend(_RRNI[msg.instance]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue