Copter: stop setting AC_Avoid in AC_WPNav; it uses singleton now

This commit is contained in:
Peter Barker 2019-06-06 10:10:19 +10:00 committed by Peter Barker
parent f2163fbc24
commit 5985579383
1 changed files with 0 additions and 5 deletions

View File

@ -151,11 +151,6 @@ void Copter::init_ardupilot()
wp_nav->set_terrain(&terrain);
#endif
#if AC_AVOID_ENABLED == ENABLED
wp_nav->set_avoidance(&avoid);
loiter_nav->set_avoidance(&avoid);
#endif
attitude_control->parameter_sanity_check();
pos_control->set_dt(scheduler.get_loop_period_s());