AC_PosControl: use AttControl's sqrt_controller

This commit is contained in:
Randy Mackay 2014-10-27 14:59:08 +09:00
parent 7224669399
commit ac7ea2a12c
1 changed files with 1 additions and 1 deletions

View File

@ -274,7 +274,7 @@ void AC_PosControl::pos_to_rate_z()
} }
// calculate _vel_target.z using from _pos_error.z using sqrt controller // calculate _vel_target.z using from _pos_error.z using sqrt controller
_vel_target.z = sqrt_controller(_pos_error.z, _p_alt_pos.kP(), _accel_z_cms); _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_alt_pos.kP(), _accel_z_cms);
// call rate based throttle controller which will update accel based throttle controller targets // call rate based throttle controller which will update accel based throttle controller targets
rate_to_accel_z(); rate_to_accel_z();