mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
5859250651
commit
9b046f5a12
|
@ -2480,19 +2480,19 @@ void GCS::update_send()
|
||||||
#if AP_MISSION_ENABLED
|
#if AP_MISSION_ENABLED
|
||||||
AP_Mission *mission = AP::mission();
|
AP_Mission *mission = AP::mission();
|
||||||
if (mission != nullptr) {
|
if (mission != nullptr) {
|
||||||
missionitemprotocols[MAV_MISSION_TYPE_MISSION] = new MissionItemProtocol_Waypoints(*mission);
|
missionitemprotocols[MAV_MISSION_TYPE_MISSION] = NEW_NOTHROW MissionItemProtocol_Waypoints(*mission);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if HAL_RALLY_ENABLED
|
#if HAL_RALLY_ENABLED
|
||||||
AP_Rally *rally = AP::rally();
|
AP_Rally *rally = AP::rally();
|
||||||
if (rally != nullptr) {
|
if (rally != nullptr) {
|
||||||
missionitemprotocols[MAV_MISSION_TYPE_RALLY] = new MissionItemProtocol_Rally(*rally);
|
missionitemprotocols[MAV_MISSION_TYPE_RALLY] = NEW_NOTHROW MissionItemProtocol_Rally(*rally);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if AP_FENCE_ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
AC_Fence *fence = AP::fence();
|
AC_Fence *fence = AP::fence();
|
||||||
if (fence != nullptr) {
|
if (fence != nullptr) {
|
||||||
missionitemprotocols[MAV_MISSION_TYPE_FENCE] = new MissionItemProtocol_Fence(*fence);
|
missionitemprotocols[MAV_MISSION_TYPE_FENCE] = NEW_NOTHROW MissionItemProtocol_Fence(*fence);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -2594,7 +2594,7 @@ void GCS::setup_uarts()
|
||||||
|
|
||||||
#if AP_FRSKY_TELEM_ENABLED
|
#if AP_FRSKY_TELEM_ENABLED
|
||||||
if (frsky == nullptr) {
|
if (frsky == nullptr) {
|
||||||
frsky = new AP_Frsky_Telem();
|
frsky = NEW_NOTHROW AP_Frsky_Telem();
|
||||||
if (frsky == nullptr || !frsky->init()) {
|
if (frsky == nullptr || !frsky->init()) {
|
||||||
delete frsky;
|
delete frsky;
|
||||||
frsky = nullptr;
|
frsky = nullptr;
|
||||||
|
@ -6389,7 +6389,7 @@ DefaultIntervalsFromFiles::DefaultIntervalsFromFiles(uint16_t max_num)
|
||||||
if (max_num == 0) {
|
if (max_num == 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_intervals = new from_file_default_interval[max_num];
|
_intervals = NEW_NOTHROW from_file_default_interval[max_num];
|
||||||
_max_intervals = max_num;
|
_max_intervals = max_num;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -6513,7 +6513,7 @@ void GCS_MAVLINK::initialise_message_intervals_from_config_files()
|
||||||
}
|
}
|
||||||
|
|
||||||
// first over-allocate:
|
// first over-allocate:
|
||||||
DefaultIntervalsFromFiles *overallocated = new DefaultIntervalsFromFiles(128);
|
DefaultIntervalsFromFiles *overallocated = NEW_NOTHROW DefaultIntervalsFromFiles(128);
|
||||||
if (overallocated == nullptr) {
|
if (overallocated == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -6531,7 +6531,7 @@ void GCS_MAVLINK::initialise_message_intervals_from_config_files()
|
||||||
delete overallocated;
|
delete overallocated;
|
||||||
overallocated = nullptr;
|
overallocated = nullptr;
|
||||||
|
|
||||||
default_intervals_from_files = new DefaultIntervalsFromFiles(num_required);
|
default_intervals_from_files = NEW_NOTHROW DefaultIntervalsFromFiles(num_required);
|
||||||
if (default_intervals_from_files == nullptr) {
|
if (default_intervals_from_files == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -55,7 +55,7 @@ protected:
|
||||||
|
|
||||||
GCS_MAVLINK_Dummy *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
GCS_MAVLINK_Dummy *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
||||||
AP_HAL::UARTDriver &uart) override {
|
AP_HAL::UARTDriver &uart) override {
|
||||||
return new GCS_MAVLINK_Dummy(params, uart);
|
return NEW_NOTHROW GCS_MAVLINK_Dummy(params, uart);
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -48,7 +48,7 @@ bool GCS_MAVLINK::ftp_init(void) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
ftp.requests = new ObjectBuffer<pending_ftp>(5);
|
ftp.requests = NEW_NOTHROW ObjectBuffer<pending_ftp>(5);
|
||||||
if (ftp.requests == nullptr || ftp.requests->get_size() == 0) {
|
if (ftp.requests == nullptr || ftp.requests->get_size() == 0) {
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
|
@ -233,7 +233,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_receive_resources(const u
|
||||||
MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_update_resources()
|
MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_update_resources()
|
||||||
{
|
{
|
||||||
const uint16_t _item_count = _fence.polyfence().num_stored_items();
|
const uint16_t _item_count = _fence.polyfence().num_stored_items();
|
||||||
_updated_mask = new uint8_t[(_item_count+7)/8];
|
_updated_mask = NEW_NOTHROW uint8_t[(_item_count+7)/8];
|
||||||
if (_updated_mask == nullptr) {
|
if (_updated_mask == nullptr) {
|
||||||
return MAV_MISSION_ERROR;
|
return MAV_MISSION_ERROR;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue