mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
global: use static method to construct AC_Avoid
This commit is contained in:
parent
e68c5a4668
commit
4f42facefc
@ -66,9 +66,6 @@ Copter::Copter(void)
|
||||
mainLoop_count(0),
|
||||
rtl_loiter_start_time(0),
|
||||
auto_trim_counter(0),
|
||||
#if AC_AVOID_ENABLED == ENABLED
|
||||
avoid(ahrs, inertial_nav, fence, g2.proximity, &g2.beacon),
|
||||
#endif
|
||||
#if SPRAYER == ENABLED
|
||||
sprayer(&inertial_nav),
|
||||
#endif
|
||||
|
@ -558,7 +558,7 @@ private:
|
||||
#endif
|
||||
|
||||
#if AC_AVOID_ENABLED == ENABLED
|
||||
AC_Avoid avoid;
|
||||
AC_Avoid avoid = AC_Avoid::create(ahrs, inertial_nav, fence, g2.proximity, &g2.beacon);
|
||||
#endif
|
||||
|
||||
// Rally library
|
||||
|
@ -51,9 +51,6 @@ Sub::Sub(void)
|
||||
pos_control(ahrs_view, inertial_nav, motors, attitude_control,
|
||||
g.p_alt_hold, g.p_vel_z, g.pid_accel_z,
|
||||
g.p_pos_xy, g.pi_vel_xy),
|
||||
#if AVOIDANCE_ENABLED == ENABLED
|
||||
avoid(ahrs, inertial_nav, fence, g2.proximity),
|
||||
#endif
|
||||
wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
|
||||
circle_nav(inertial_nav, ahrs_view, pos_control),
|
||||
pmTest1(0),
|
||||
|
@ -390,10 +390,6 @@ private:
|
||||
|
||||
AC_PosControl_Sub pos_control;
|
||||
|
||||
#if AVOIDANCE_ENABLED == ENABLED
|
||||
AC_Avoid avoid;
|
||||
#endif
|
||||
|
||||
AC_WPNav wp_nav;
|
||||
AC_Circle circle_nav;
|
||||
|
||||
@ -429,6 +425,10 @@ private:
|
||||
AC_Fence fence = AC_Fence::create(ahrs, inertial_nav);
|
||||
#endif
|
||||
|
||||
#if AVOIDANCE_ENABLED == ENABLED
|
||||
AC_Avoid avoid = AC_Avoid::create(ahrs, inertial_nav, fence, g2.proximity, &g2.beacon);
|
||||
#endif
|
||||
|
||||
// Rally library
|
||||
#if AC_RALLY == ENABLED
|
||||
AP_Rally rally = AP_Rally::create(ahrs);
|
||||
|
Loading…
Reference in New Issue
Block a user