From 00037fd50e49319fd05798c3d7a3b64fe2951eac Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 20 Nov 2017 15:58:25 +0900 Subject: [PATCH] AC_PosControl_Sub: replace velocity pi with local pid --- libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp | 4 ++-- libraries/AC_AttitudeControl/AC_PosControl_Sub.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp index ac35222dbc..0389f74e4c 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp @@ -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) {} diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Sub.h b/libraries/AC_AttitudeControl/AC_PosControl_Sub.h index 98dad4cc32..f2dc5198e6 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl_Sub.h +++ b/libraries/AC_AttitudeControl/AC_PosControl_Sub.h @@ -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