Browse Source

global: use static method to construct AC_Fence

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
c6eb48009b
  1. 3
      ArduCopter/Copter.cpp
  2. 3
      ArduCopter/Copter.h
  3. 3
      ArduSub/Sub.cpp
  4. 2
      ArduSub/Sub.h

3
ArduCopter/Copter.cpp

@ -66,9 +66,6 @@ Copter::Copter(void) @@ -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

3
ArduCopter/Copter.h

@ -554,8 +554,9 @@ private: @@ -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

3
ArduSub/Sub.cpp

@ -59,9 +59,6 @@ Sub::Sub(void) @@ -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

2
ArduSub/Sub.h

@ -426,7 +426,7 @@ private: @@ -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…
Cancel
Save