mirror of https://github.com/ArduPilot/ardupilot
AP_OpenDroneID: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
cead1ee264
commit
014b3bba70
|
@ -42,35 +42,35 @@ void AP_OpenDroneID::dronecan_init(AP_DroneCAN *uavcan)
|
|||
return;
|
||||
}
|
||||
|
||||
dc_location[driver_index] = new Canard::Publisher<dronecan_remoteid_Location>(uavcan->get_canard_iface());
|
||||
dc_location[driver_index] = NEW_NOTHROW Canard::Publisher<dronecan_remoteid_Location>(uavcan->get_canard_iface());
|
||||
if (dc_location[driver_index] == nullptr) {
|
||||
goto alloc_failed;
|
||||
}
|
||||
dc_location[driver_index]->set_timeout_ms(20);
|
||||
dc_location[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW);
|
||||
|
||||
dc_basic_id[driver_index] = new Canard::Publisher<dronecan_remoteid_BasicID>(uavcan->get_canard_iface());
|
||||
dc_basic_id[driver_index] = NEW_NOTHROW Canard::Publisher<dronecan_remoteid_BasicID>(uavcan->get_canard_iface());
|
||||
if (dc_basic_id[driver_index] == nullptr) {
|
||||
goto alloc_failed;
|
||||
}
|
||||
dc_basic_id[driver_index]->set_timeout_ms(20);
|
||||
dc_basic_id[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW);
|
||||
|
||||
dc_self_id[driver_index] = new Canard::Publisher<dronecan_remoteid_SelfID>(uavcan->get_canard_iface());
|
||||
dc_self_id[driver_index] = NEW_NOTHROW Canard::Publisher<dronecan_remoteid_SelfID>(uavcan->get_canard_iface());
|
||||
if (dc_self_id[driver_index] == nullptr) {
|
||||
goto alloc_failed;
|
||||
}
|
||||
dc_self_id[driver_index]->set_timeout_ms(20);
|
||||
dc_self_id[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW);
|
||||
|
||||
dc_system[driver_index] = new Canard::Publisher<dronecan_remoteid_System>(uavcan->get_canard_iface());
|
||||
dc_system[driver_index] = NEW_NOTHROW Canard::Publisher<dronecan_remoteid_System>(uavcan->get_canard_iface());
|
||||
if (dc_system[driver_index] == nullptr) {
|
||||
goto alloc_failed;
|
||||
}
|
||||
dc_system[driver_index]->set_timeout_ms(20);
|
||||
dc_system[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW);
|
||||
|
||||
dc_operator_id[driver_index] = new Canard::Publisher<dronecan_remoteid_OperatorID>(uavcan->get_canard_iface());
|
||||
dc_operator_id[driver_index] = NEW_NOTHROW Canard::Publisher<dronecan_remoteid_OperatorID>(uavcan->get_canard_iface());
|
||||
if (dc_operator_id[driver_index] == nullptr) {
|
||||
goto alloc_failed;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue