mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
global: use static method to construct AC_Fence
This commit is contained in:
parent
52686ec838
commit
c6eb48009b
@ -66,9 +66,6 @@ Copter::Copter(void)
|
||||
mainLoop_count(0),
|
||||
rtl_loiter_start_time(0),
|
||||
auto_trim_counter(0),
|
||||
#if AC_FENCE == ENABLED
|
||||
fence(ahrs, inertial_nav),
|
||||
#endif
|
||||
#if AC_AVOID_ENABLED == ENABLED
|
||||
avoid(ahrs, inertial_nav, fence, g2.proximity, &g2.beacon),
|
||||
#endif
|
||||
|
@ -554,8 +554,9 @@ private:
|
||||
|
||||
// AC_Fence library to reduce fly-aways
|
||||
#if AC_FENCE == ENABLED
|
||||
AC_Fence fence;
|
||||
AC_Fence fence = AC_Fence::create(ahrs, inertial_nav);
|
||||
#endif
|
||||
|
||||
#if AC_AVOID_ENABLED == ENABLED
|
||||
AC_Avoid avoid;
|
||||
#endif
|
||||
|
@ -59,9 +59,6 @@ Sub::Sub(void)
|
||||
pmTest1(0),
|
||||
fast_loopTimer(0),
|
||||
mainLoop_count(0),
|
||||
#if AC_FENCE == ENABLED
|
||||
fence(ahrs, inertial_nav),
|
||||
#endif
|
||||
#if AC_RALLY == ENABLED
|
||||
rally(ahrs),
|
||||
#endif
|
||||
|
@ -426,7 +426,7 @@ private:
|
||||
|
||||
// AC_Fence library to reduce fly-aways
|
||||
#if AC_FENCE == ENABLED
|
||||
AC_Fence fence;
|
||||
AC_Fence fence = AC_Fence::create(ahrs, inertial_nav);
|
||||
#endif
|
||||
|
||||
// Rally library
|
||||
|
Loading…
Reference in New Issue
Block a user