mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Blimp: use allocation_error instead of panic on allocation failure
This commit is contained in:
parent
a55bd3955a
commit
8a3e1b96ab
@ -263,7 +263,7 @@ void Blimp::allocate_motors(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (motors == nullptr) {
|
if (motors == nullptr) {
|
||||||
AP_HAL::panic("Unable to allocate FRAME_CLASS=%u", (unsigned)g2.frame_class.get());
|
AP_BoardConfig::allocation_error("Unable to allocate FRAME_CLASS=%u", (unsigned)g2.frame_class.get());
|
||||||
}
|
}
|
||||||
AP_Param::load_object_from_eeprom(motors, Fins::var_info);
|
AP_Param::load_object_from_eeprom(motors, Fins::var_info);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user