Copter: replace config_error with allocation_error

This commit is contained in:
bugobliterator 2021-09-23 13:21:51 +05:30 committed by Peter Barker
parent fd369e8262
commit 2751afaa75

View File

@ -493,13 +493,13 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
#endif
}
if (motors == nullptr) {
AP_BoardConfig::config_error("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, motors_var_info);
ahrs_view = ahrs.create_view(ROTATION_NONE);
if (ahrs_view == nullptr) {
AP_BoardConfig::config_error("Unable to allocate AP_AHRS_View");
AP_BoardConfig::allocation_error("Unable to allocate AP_AHRS_View");
}
const struct AP_Param::GroupInfo *ac_var_info;
@ -519,13 +519,13 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
ac_var_info = AC_AttitudeControl_Heli::var_info;
#endif
if (attitude_control == nullptr) {
AP_BoardConfig::config_error("Unable to allocate AttitudeControl");
AP_BoardConfig::allocation_error("Unable to allocate AttitudeControl");
}
AP_Param::load_object_from_eeprom(attitude_control, ac_var_info);
pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control, scheduler.get_loop_period_s());
if (pos_control == nullptr) {
AP_BoardConfig::config_error("Unable to allocate PosControl");
AP_BoardConfig::allocation_error("Unable to allocate PosControl");
}
AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info);
@ -535,20 +535,20 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
wp_nav = new AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
#endif
if (wp_nav == nullptr) {
AP_BoardConfig::config_error("Unable to allocate WPNav");
AP_BoardConfig::allocation_error("Unable to allocate WPNav");
}
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
loiter_nav = new AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
if (loiter_nav == nullptr) {
AP_BoardConfig::config_error("Unable to allocate LoiterNav");
AP_BoardConfig::allocation_error("Unable to allocate LoiterNav");
}
AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info);
#if MODE_CIRCLE_ENABLED == ENABLED
circle_nav = new AC_Circle(inertial_nav, *ahrs_view, *pos_control);
if (circle_nav == nullptr) {
AP_BoardConfig::config_error("Unable to allocate CircleNav");
AP_BoardConfig::allocation_error("Unable to allocate CircleNav");
}
AP_Param::load_object_from_eeprom(circle_nav, circle_nav->var_info);
#endif