mirror of https://github.com/ArduPilot/ardupilot
Rover: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
91ff1bc028
commit
5113b6af59
|
@ -32,7 +32,7 @@ protected:
|
|||
|
||||
GCS_MAVLINK_Rover *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
||||
AP_HAL::UARTDriver &uart) override {
|
||||
return new GCS_MAVLINK_Rover(params, uart);
|
||||
return NEW_NOTHROW GCS_MAVLINK_Rover(params, uart);
|
||||
}
|
||||
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue