mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
c70c8657bc
commit
1e075aeb80
|
@ -633,7 +633,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
|||
case GPS_TYPE_MAV:
|
||||
#if AP_GPS_MAV_ENABLED
|
||||
dstate->auto_detected_baud = false; // specified, not detected
|
||||
return new AP_GPS_MAV(*this, params[instance], state[instance], nullptr);
|
||||
return NEW_NOTHROW AP_GPS_MAV(*this, params[instance], state[instance], nullptr);
|
||||
#endif //AP_GPS_MAV_ENABLED
|
||||
|
||||
// user has to explicitly set the UAVCAN type, do not use AUTO
|
||||
|
@ -648,17 +648,17 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
|||
#if HAL_MSP_GPS_ENABLED
|
||||
case GPS_TYPE_MSP:
|
||||
dstate->auto_detected_baud = false; // specified, not detected
|
||||
return new AP_GPS_MSP(*this, params[instance], state[instance], nullptr);
|
||||
return NEW_NOTHROW AP_GPS_MSP(*this, params[instance], state[instance], nullptr);
|
||||
#endif
|
||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||
case GPS_TYPE_EXTERNAL_AHRS:
|
||||
dstate->auto_detected_baud = false; // specified, not detected
|
||||
return new AP_GPS_ExternalAHRS(*this, params[instance], state[instance], nullptr);
|
||||
return NEW_NOTHROW AP_GPS_ExternalAHRS(*this, params[instance], state[instance], nullptr);
|
||||
#endif
|
||||
#if AP_GPS_GSOF_ENABLED
|
||||
case GPS_TYPE_GSOF:
|
||||
dstate->auto_detected_baud = false; // specified, not detected
|
||||
return new AP_GPS_GSOF(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_GSOF(*this, params[instance], state[instance], _port[instance]);
|
||||
#endif //AP_GPS_GSOF_ENABLED
|
||||
default:
|
||||
break;
|
||||
|
@ -712,16 +712,16 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
|||
// by default the sbf/trimble gps outputs no data on its port, until configured.
|
||||
case GPS_TYPE_SBF:
|
||||
case GPS_TYPE_SBF_DUAL_ANTENNA:
|
||||
return new AP_GPS_SBF(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_SBF(*this, params[instance], state[instance], _port[instance]);
|
||||
#endif //AP_GPS_SBF_ENABLED
|
||||
#if AP_GPS_NOVA_ENABLED
|
||||
case GPS_TYPE_NOVA:
|
||||
return new AP_GPS_NOVA(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_NOVA(*this, params[instance], state[instance], _port[instance]);
|
||||
#endif //AP_GPS_NOVA_ENABLED
|
||||
|
||||
#if HAL_SIM_GPS_ENABLED
|
||||
case GPS_TYPE_SITL:
|
||||
return new AP_GPS_SITL(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_SITL(*this, params[instance], state[instance], _port[instance]);
|
||||
#endif // HAL_SIM_GPS_ENABLED
|
||||
|
||||
default:
|
||||
|
@ -746,7 +746,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
|||
(_baudrates[dstate->current_baud] >= 115200 && option_set(DriverOptions::UBX_Use115200)) ||
|
||||
_baudrates[dstate->current_baud] == 230400) &&
|
||||
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
|
||||
return new AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], GPS_ROLE_NORMAL);
|
||||
return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], GPS_ROLE_NORMAL);
|
||||
}
|
||||
|
||||
const uint32_t ublox_mb_required_baud = option_set(DriverOptions::UBX_MBUseUart2)?230400:460800;
|
||||
|
@ -760,31 +760,31 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
|||
} else {
|
||||
role = GPS_ROLE_MB_ROVER;
|
||||
}
|
||||
return new AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], role);
|
||||
return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], role);
|
||||
}
|
||||
#endif // AP_GPS_UBLOX_ENABLED
|
||||
#if AP_GPS_SBP2_ENABLED
|
||||
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) &&
|
||||
AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {
|
||||
return new AP_GPS_SBP2(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_SBP2(*this, params[instance], state[instance], _port[instance]);
|
||||
}
|
||||
#endif //AP_GPS_SBP2_ENABLED
|
||||
#if AP_GPS_SBP_ENABLED
|
||||
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) &&
|
||||
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
|
||||
return new AP_GPS_SBP(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_SBP(*this, params[instance], state[instance], _port[instance]);
|
||||
}
|
||||
#endif //AP_GPS_SBP_ENABLED
|
||||
#if AP_GPS_SIRF_ENABLED
|
||||
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SIRF) &&
|
||||
AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
|
||||
return new AP_GPS_SIRF(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_SIRF(*this, params[instance], state[instance], _port[instance]);
|
||||
}
|
||||
#endif
|
||||
#if AP_GPS_ERB_ENABLED
|
||||
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_ERB) &&
|
||||
AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) {
|
||||
return new AP_GPS_ERB(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_ERB(*this, params[instance], state[instance], _port[instance]);
|
||||
}
|
||||
#endif // AP_GPS_ERB_ENABLED
|
||||
#if AP_GPS_NMEA_ENABLED
|
||||
|
@ -796,7 +796,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
|||
#endif
|
||||
type == GPS_TYPE_ALLYSTAR) &&
|
||||
AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {
|
||||
return new AP_GPS_NMEA(*this, params[instance], state[instance], _port[instance]);
|
||||
return NEW_NOTHROW AP_GPS_NMEA(*this, params[instance], state[instance], _port[instance]);
|
||||
}
|
||||
#endif //AP_GPS_NMEA_ENABLED
|
||||
}
|
||||
|
@ -1618,7 +1618,7 @@ bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm
|
|||
return false;
|
||||
}
|
||||
if (rtcm.parsers[chan] == nullptr) {
|
||||
rtcm.parsers[chan] = new RTCM3_Parser();
|
||||
rtcm.parsers[chan] = NEW_NOTHROW RTCM3_Parser();
|
||||
if (rtcm.parsers[chan] == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -170,14 +170,14 @@ AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state)
|
|||
// initialise the backend based on the UAVCAN Moving baseline selection
|
||||
switch (_gps.get_type(_state.instance)) {
|
||||
case AP_GPS::GPS_TYPE_UAVCAN:
|
||||
backend = new AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_NORMAL);
|
||||
backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_NORMAL);
|
||||
break;
|
||||
#if GPS_MOVING_BASELINE
|
||||
case AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE:
|
||||
backend = new AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_BASE);
|
||||
backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_BASE);
|
||||
break;
|
||||
case AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER:
|
||||
backend = new AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_ROVER);
|
||||
backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_ROVER);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
|
@ -214,7 +214,7 @@ AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state)
|
|||
}
|
||||
#if GPS_MOVING_BASELINE
|
||||
if (backend->role == AP_GPS::GPS_ROLE_MB_BASE) {
|
||||
backend->rtcm3_parser = new RTCM3_Parser;
|
||||
backend->rtcm3_parser = NEW_NOTHROW RTCM3_Parser;
|
||||
if (backend->rtcm3_parser == nullptr) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DroneCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id);
|
||||
}
|
||||
|
@ -822,7 +822,7 @@ void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len)
|
|||
if (_rtcm_stream.buf == nullptr) {
|
||||
// give enough space for a full round from a NTRIP server with all
|
||||
// constellations
|
||||
_rtcm_stream.buf = new ByteBuffer(2400);
|
||||
_rtcm_stream.buf = NEW_NOTHROW ByteBuffer(2400);
|
||||
if (_rtcm_stream.buf == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -120,7 +120,7 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps,
|
|||
|
||||
#if GPS_MOVING_BASELINE
|
||||
if (role == AP_GPS::GPS_ROLE_MB_BASE && !mb_use_uart2()) {
|
||||
rtcm3_parser = new RTCM3_Parser;
|
||||
rtcm3_parser = NEW_NOTHROW RTCM3_Parser;
|
||||
if (rtcm3_parser == nullptr) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "u-blox %d: failed RTCMv3 parser allocation", state.instance + 1);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue