diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index bb2d3bc2f67879..171c974c565009 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -448,6 +448,9 @@ void Copter::allocate_motors(void) AP_BoardConfig::allocation_error("PosControl"); } AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info); +#if AP_AVOIDANCE_ENABLED + avoid.set_pos_control(pos_control); +#endif #if AP_OAPATHPLANNER_ENABLED wp_nav = new AC_WPNav_OA(inertial_nav, *ahrs_view, *pos_control, *attitude_control);