diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 0c84337300..6a739acdf8 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -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);