mirror of https://github.com/ArduPilot/ardupilot
Sub: stop setting AC_Avoid in AC_WPNav; it uses singleton now
This commit is contained in:
parent
5985579383
commit
4c4d37bd86
|
@ -118,11 +118,6 @@ void Sub::init_ardupilot()
|
||||||
wp_nav.set_terrain(&terrain);
|
wp_nav.set_terrain(&terrain);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AVOIDANCE_ENABLED == ENABLED
|
|
||||||
wp_nav.set_avoidance(&avoid);
|
|
||||||
loiter_nav.set_avoidance(&avoid);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
pos_control.set_dt(MAIN_LOOP_SECONDS);
|
pos_control.set_dt(MAIN_LOOP_SECONDS);
|
||||||
|
|
||||||
// init the optical flow sensor
|
// init the optical flow sensor
|
||||||
|
|
Loading…
Reference in New Issue