From f24a0988f422a864fe17fa53e9f2d7ee33500e2b Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 12 May 2021 13:17:38 +0900 Subject: [PATCH] AC_PosControl: minor formatting fixes --- libraries/AC_AttitudeControl/AC_PosControl.h | 46 ++++++++++---------- 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 351c4cc763..1dd2153d11 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -3,17 +3,17 @@ #include #include #include -#include // P library -#include // PID library -#include // P library (1-axis) -#include // P library (2-axis) -#include // PI library (2-axis) -#include // PID library (1-axis) -#include // PID library (2-axis) -#include // Inertial Navigation library -#include "AC_AttitudeControl.h" // Attitude control library -#include // motors library -#include // common vehicle parameters +#include // P library +#include // PID library +#include // P library (1-axis) +#include // P library (2-axis) +#include // PI library (2-axis) +#include // PID library (1-axis) +#include // PID library (2-axis) +#include // Inertial Navigation library +#include "AC_AttitudeControl.h" // Attitude control library +#include // motors library +#include // common vehicle parameters // position controller default definitions @@ -386,10 +386,10 @@ protected: void check_for_ekf_z_reset(); // references to inertial nav and ahrs libraries - AP_AHRS_View & _ahrs; - const AP_InertialNav& _inav; - const AP_Motors& _motors; - AC_AttitudeControl& _attitude_control; + AP_AHRS_View& _ahrs; + const AP_InertialNav& _inav; + const AP_Motors& _motors; + AC_AttitudeControl& _attitude_control; // parameters AP_Float _accel_xy_filt_hz; // XY acceleration filter cutoff frequency @@ -418,17 +418,17 @@ protected: // output from controller float _roll_target; // desired roll angle in centi-degrees calculated by position controller float _pitch_target; // desired roll pitch in centi-degrees calculated by position controller - float _yaw_target; // desired yaw in centi-degrees calculated by position controller - float _yaw_rate_target; // desired yaw rate in centi-degrees per second calculated by position controller + float _yaw_target; // desired yaw in centi-degrees calculated by position controller + float _yaw_rate_target; // desired yaw rate in centi-degrees per second calculated by position controller // position controller internal variables - Vector3f _pos_target; // target location in cm from home - Vector3f _vel_desired; // desired velocity in cm/s - Vector3f _vel_target; // velocity target in cm/s calculated by pos_to_rate step + Vector3f _pos_target; // target location in NEU cm from home + Vector3f _vel_desired; // desired velocity in NEU cm/s + Vector3f _vel_target; // velocity target in NEU cm/s calculated by pos_to_rate step Vector3f _vel_error; // error between desired and actual acceleration in cm/s - Vector3f _accel_desired; // desired acceleration in cm/s/s (feed forward) - Vector3f _accel_target; // acceleration target in cm/s/s - Vector3f _accel_error; // acceleration error in cm/s/s + Vector3f _accel_desired; // desired acceleration in NEU cm/s/s (feed forward) + Vector3f _accel_target; // acceleration target in NEU cm/s/s + Vector3f _accel_error; // acceleration error in NEU cm/s/s Vector2f _vehicle_horiz_vel; // velocity to use if _flags.vehicle_horiz_vel_override is set LowPassFilterFloat _vel_error_filter; // low-pass-filter on z-axis velocity error