Copter: remove precision landing PI controller

This controller has been moved into the precision landing class
This commit is contained in:
Randy Mackay 2015-12-31 15:27:29 +09:00
parent bea69521c8
commit 1155b1f557
3 changed files with 1 additions and 32 deletions

View File

@ -115,7 +115,7 @@ Copter::Copter(void) :
terrain(ahrs, mission, rally), terrain(ahrs, mission, rally),
#endif #endif
#if PRECISION_LANDING == ENABLED #if PRECISION_LANDING == ENABLED
precland(ahrs, inertial_nav, g.pi_precland, MAIN_LOOP_SECONDS), precland(ahrs, inertial_nav, MAIN_LOOP_SECONDS),
#endif #endif
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
// ToDo: Input Manager is only used by Heli for 3.3, but will be used by all frames for 3.4 // ToDo: Input Manager is only used by Heli for 3.3, but will be used by all frames for 3.4

View File

@ -842,28 +842,6 @@ const AP_Param::Info Copter::var_info[] = {
// @User: Standard // @User: Standard
GGROUP(p_pos_xy, "POS_XY_", AC_P), GGROUP(p_pos_xy, "POS_XY_", AC_P),
#if PRECISION_LANDING == ENABLED
// @Param: PRECLNDVEL_P
// @DisplayName: Precision landing velocity controller P gain
// @Description: Precision landing velocity controller P gain
// @Range: 0.100 5.000
// @User: Advanced
// @Param: PRECLNDVEL_I
// @DisplayName: Precision landing velocity controller I gain
// @Description: Precision landing velocity controller I gain
// @Range: 0.100 5.000
// @User: Advanced
// @Param: PRECLNDVEL_IMAX
// @DisplayName: Precision landing velocity controller I gain maximum
// @Description: Precision landing velocity controller I gain maximum
// @Range: 0 1000
// @Units: cm/s
// @User: Standard
GGROUP(pi_precland, "PLAND_", AC_PI_2D),
#endif
// variables not in the g class which contain EEPROM saved variables // variables not in the g class which contain EEPROM saved variables
#if CAMERA == ENABLED #if CAMERA == ENABLED

View File

@ -356,7 +356,6 @@ public:
k_param_rtl_climb_min, k_param_rtl_climb_min,
k_param_rpm_sensor, k_param_rpm_sensor,
k_param_autotune_min_d, // 251 k_param_autotune_min_d, // 251
k_param_pi_precland, // 252
k_param_DataFlash = 253, // 253 - Logging Group k_param_DataFlash = 253, // 253 - Logging Group
// 254,255: reserved // 254,255: reserved
@ -509,10 +508,6 @@ public:
AC_P p_vel_z; AC_P p_vel_z;
AC_PID pid_accel_z; AC_PID pid_accel_z;
#if PRECISION_LANDING == ENABLED
AC_PI_2D pi_precland;
#endif
AC_P p_pos_xy; AC_P p_pos_xy;
AC_P p_stabilize_roll; AC_P p_stabilize_roll;
AC_P p_stabilize_pitch; AC_P p_stabilize_pitch;
@ -583,10 +578,6 @@ public:
p_vel_z (VEL_Z_P), p_vel_z (VEL_Z_P),
pid_accel_z (ACCEL_Z_P, ACCEL_Z_I, ACCEL_Z_D, ACCEL_Z_IMAX, ACCEL_Z_FILT_HZ, MAIN_LOOP_SECONDS), pid_accel_z (ACCEL_Z_P, ACCEL_Z_I, ACCEL_Z_D, ACCEL_Z_IMAX, ACCEL_Z_FILT_HZ, MAIN_LOOP_SECONDS),
#if PRECISION_LANDING == ENABLED
pi_precland (PRECLAND_P, PRECLAND_I, PRECLAND_IMAX, VEL_XY_FILT_HZ, PRECLAND_UPDATE_TIME),
#endif
// P controller initial P // P controller initial P
//---------------------------------------------------------------------- //----------------------------------------------------------------------
p_pos_xy (POS_XY_P), p_pos_xy (POS_XY_P),