From ebd864d2d2de9de46b72db002460a556fd6fa7e3 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 27 Jun 2017 22:14:23 +0900 Subject: [PATCH] AC_PosControl: minor update to comments --- libraries/AC_AttitudeControl/AC_PosControl.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index d9c0388a4b..510a3d2749 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -418,9 +418,9 @@ protected: Vector3f _vel_target; // velocity target in cm/s calculated by pos_to_rate step Vector3f _vel_error; // error between desired and actual acceleration in cm/s Vector3f _vel_last; // previous iterations velocity in cm/s - Vector3f _accel_target; // desired acceleration in cm/s/s // To-Do: are xy actually required? - Vector3f _accel_error; // desired acceleration in cm/s/s // To-Do: are xy actually required? Vector3f _accel_feedforward; // feedforward acceleration in cm/s/s + Vector3f _accel_target; // acceleration target in cm/s/s + Vector3f _accel_error; // acceleration error in cm/s/s Vector2f _vehicle_horiz_vel; // velocity to use if _flags.vehicle_horiz_vel_override is set float _distance_to_target; // distance to position target - for reporting only LowPassFilterFloat _vel_error_filter; // low-pass-filter on z-axis velocity error