mirror of https://github.com/ArduPilot/ardupilot
Blimp: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
74dc4f961c
commit
91ff1bc028
|
@ -41,7 +41,7 @@ protected:
|
||||||
GCS_MAVLINK_Blimp *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
GCS_MAVLINK_Blimp *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
||||||
AP_HAL::UARTDriver &uart) override
|
AP_HAL::UARTDriver &uart) override
|
||||||
{
|
{
|
||||||
return new GCS_MAVLINK_Blimp(params, uart);
|
return NEW_NOTHROW GCS_MAVLINK_Blimp(params, uart);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -33,7 +33,7 @@ void Blimp::init_ardupilot()
|
||||||
|
|
||||||
// allocate the motors class
|
// allocate the motors class
|
||||||
allocate_motors();
|
allocate_motors();
|
||||||
loiter = new Loiter(blimp.scheduler.get_loop_rate_hz());
|
loiter = NEW_NOTHROW Loiter(blimp.scheduler.get_loop_rate_hz());
|
||||||
|
|
||||||
// initialise rc channels including setting mode
|
// initialise rc channels including setting mode
|
||||||
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
|
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
|
||||||
|
@ -240,7 +240,7 @@ void Blimp::allocate_motors(void)
|
||||||
switch ((Fins::motor_frame_class)g2.frame_class.get()) {
|
switch ((Fins::motor_frame_class)g2.frame_class.get()) {
|
||||||
case Fins::MOTOR_FRAME_AIRFISH:
|
case Fins::MOTOR_FRAME_AIRFISH:
|
||||||
default:
|
default:
|
||||||
motors = new Fins(blimp.scheduler.get_loop_rate_hz());
|
motors = NEW_NOTHROW Fins(blimp.scheduler.get_loop_rate_hz());
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (motors == nullptr) {
|
if (motors == nullptr) {
|
||||||
|
|
Loading…
Reference in New Issue