Browse Source

Copter: correct nullptr check for circle nav allocation

master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
1a68979050
  1. 2
      ArduCopter/system.cpp

2
ArduCopter/system.cpp

@ -610,7 +610,7 @@ void Copter::allocate_motors(void) @@ -610,7 +610,7 @@ void Copter::allocate_motors(void)
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
circle_nav = new AC_Circle(inertial_nav, *ahrs_view, *pos_control);
if (wp_nav == nullptr) {
if (circle_nav == nullptr) {
AP_HAL::panic("Unable to allocate CircleNav");
}
AP_Param::load_object_from_eeprom(circle_nav, circle_nav->var_info);

Loading…
Cancel
Save