AC_PosControl_Sub: replace velocity pi with local pid

This commit is contained in:
Randy Mackay 2017-11-20 15:58:25 +09:00
parent 3a73ff1e2e
commit 00037fd50e
2 changed files with 3 additions and 3 deletions

View File

@ -3,8 +3,8 @@
AC_PosControl_Sub::AC_PosControl_Sub(const AP_AHRS_View& ahrs, const AP_InertialNav& inav,
const AP_Motors& motors, AC_AttitudeControl& attitude_control,
AC_P& p_pos_z, AC_P& p_vel_z, AC_PID& pid_accel_z,
AC_P& p_pos_xy, AC_PI_2D& pi_vel_xy) :
AC_PosControl(ahrs, inav, motors, attitude_control, p_pos_z, p_vel_z, pid_accel_z, p_pos_xy, pi_vel_xy),
AC_P& p_pos_xy) :
AC_PosControl(ahrs, inav, motors, attitude_control, p_pos_z, p_vel_z, pid_accel_z, p_pos_xy),
_alt_max(0.0f),
_alt_min(0.0f)
{}

View File

@ -7,7 +7,7 @@ public:
AC_PosControl_Sub(const AP_AHRS_View & ahrs, const AP_InertialNav& inav,
const AP_Motors& motors, AC_AttitudeControl& attitude_control,
AC_P& p_pos_z, AC_P& p_vel_z, AC_PID& pid_accel_z,
AC_P& p_pos_xy, AC_PI_2D& pi_vel_xy);
AC_P& p_pos_xy);
/// set_alt_max - sets maximum altitude above the ekf origin in cm
/// only enforced when set_alt_target_from_climb_rate is used