Copter: rename loiter_pos to pos_xy
Also renamed throttle_rate to vel_z, throttle_accel to accel_z
This commit is contained in:
parent
e232867661
commit
c78480e14f
@ -623,8 +623,8 @@ AC_AttitudeControl attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p
|
||||
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
|
||||
#endif
|
||||
AC_PosControl pos_control(ahrs, inertial_nav, motors, attitude_control,
|
||||
g.p_alt_hold, g.p_throttle_rate, g.pid_throttle_accel,
|
||||
g.p_loiter_pos, g.pi_vel_xy);
|
||||
g.p_alt_hold, g.p_vel_z, g.pid_accel_z,
|
||||
g.p_pos_xy, g.pi_vel_xy);
|
||||
static AC_WPNav wp_nav(inertial_nav, ahrs, pos_control, attitude_control);
|
||||
static AC_Circle circle_nav(inertial_nav, ahrs, pos_control);
|
||||
|
||||
|
@ -272,5 +272,5 @@ static float get_throttle_surface_tracking(int16_t target_rate, float current_al
|
||||
static void set_accel_throttle_I_from_pilot_throttle(int16_t pilot_throttle)
|
||||
{
|
||||
// shift difference between pilot's throttle and hover throttle into accelerometer I
|
||||
g.pid_throttle_accel.set_integrator(pilot_throttle-g.throttle_cruise);
|
||||
g.pid_accel_z.set_integrator(pilot_throttle-g.throttle_cruise);
|
||||
}
|
||||
|
@ -299,19 +299,19 @@ public:
|
||||
k_param_p_stabilize_roll,
|
||||
k_param_p_stabilize_pitch,
|
||||
k_param_p_stabilize_yaw,
|
||||
k_param_p_loiter_pos,
|
||||
k_param_p_pos_xy,
|
||||
k_param_p_loiter_lon, // remove
|
||||
k_param_pid_loiter_rate_lat, // remove
|
||||
k_param_pid_loiter_rate_lon, // remove
|
||||
k_param_pid_nav_lat, // 233 - remove
|
||||
k_param_pid_nav_lon, // 234 - remove
|
||||
k_param_p_alt_hold,
|
||||
k_param_p_throttle_rate,
|
||||
k_param_p_vel_z,
|
||||
k_param_pid_optflow_roll, // 237 - remove
|
||||
k_param_pid_optflow_pitch, // 238 - remove
|
||||
k_param_acro_balance_roll_old, // 239 - remove
|
||||
k_param_acro_balance_pitch_old, // 240 - remove
|
||||
k_param_pid_throttle_accel,
|
||||
k_param_pid_accel_z,
|
||||
k_param_acro_balance_roll,
|
||||
k_param_acro_balance_pitch,
|
||||
k_param_acro_yaw_p, // 244
|
||||
@ -455,10 +455,10 @@ public:
|
||||
#endif
|
||||
AC_PI_2D pi_vel_xy;
|
||||
|
||||
AC_P p_throttle_rate;
|
||||
AC_PID pid_throttle_accel;
|
||||
AC_P p_vel_z;
|
||||
AC_PID pid_accel_z;
|
||||
|
||||
AC_P p_loiter_pos;
|
||||
AC_P p_pos_xy;
|
||||
AC_P p_stabilize_roll;
|
||||
AC_P p_stabilize_pitch;
|
||||
AC_P p_stabilize_yaw;
|
||||
@ -517,12 +517,12 @@ public:
|
||||
|
||||
pi_vel_xy (VEL_XY_P, VEL_XY_I, VEL_XY_IMAX, VEL_XY_FILT_HZ, WPNAV_LOITER_UPDATE_TIME),
|
||||
|
||||
p_throttle_rate (THROTTLE_RATE_P),
|
||||
pid_throttle_accel (THROTTLE_ACCEL_P,THROTTLE_ACCEL_I, THROTTLE_ACCEL_D,THROTTLE_ACCEL_IMAX, THROTTLE_ACCEL_FILT_HZ, MAIN_LOOP_SECONDS),
|
||||
p_vel_z (VEL_Z_P),
|
||||
pid_accel_z (ACCEL_Z_P, ACCEL_Z_I, ACCEL_Z_D, ACCEL_Z_IMAX, ACCEL_Z_FILT_HZ, MAIN_LOOP_SECONDS),
|
||||
|
||||
// P controller initial P
|
||||
//----------------------------------------------------------------------
|
||||
p_loiter_pos (LOITER_POS_P),
|
||||
p_pos_xy (POS_XY_P),
|
||||
|
||||
p_stabilize_roll (STABILIZE_ROLL_P),
|
||||
p_stabilize_pitch (STABILIZE_PITCH_P),
|
||||
|
@ -703,57 +703,38 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
GGROUP(pi_vel_xy, "VEL_XY_", AC_PI_2D),
|
||||
|
||||
// @Param: THR_RATE_P
|
||||
// @DisplayName: Throttle rate controller P gain
|
||||
// @Description: Throttle rate controller P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
|
||||
// @Param: VEL_Z_P
|
||||
// @DisplayName: Velocity (vertical) P gain
|
||||
// @Description: Velocity (vertical) P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
|
||||
// @Range: 1.000 8.000
|
||||
// @User: Standard
|
||||
GGROUP(p_vel_z, "VEL_Z_", AC_P),
|
||||
|
||||
// @Param: THR_RATE_I
|
||||
// @DisplayName: Throttle rate controller I gain
|
||||
// @Description: Throttle rate controller I gain. Corrects long-term difference in desired vertical speed and actual speed
|
||||
// @Range: 0.000 0.100
|
||||
// @User: Standard
|
||||
|
||||
// @Param: THR_RATE_IMAX
|
||||
// @DisplayName: Throttle rate controller I gain maximum
|
||||
// @Description: Throttle rate controller I gain maximum. Constrains the desired acceleration that the I gain will generate
|
||||
// @Range: 0 500
|
||||
// @Units: cm/s/s
|
||||
// @User: Standard
|
||||
|
||||
// @Param: THR_RATE_D
|
||||
// @DisplayName: Throttle rate controller D gain
|
||||
// @Description: Throttle rate controller D gain. Compensates for short-term change in desired vertical speed vs actual speed
|
||||
// @Range: 0.000 0.400
|
||||
// @User: Standard
|
||||
GGROUP(p_throttle_rate, "THR_RATE_", AC_P),
|
||||
|
||||
// @Param: THR_ACCEL_P
|
||||
// @Param: ACCEL_Z_P
|
||||
// @DisplayName: Throttle acceleration controller P gain
|
||||
// @Description: Throttle acceleration controller P gain. Converts the difference between desired vertical acceleration and actual acceleration into a motor output
|
||||
// @Range: 0.500 1.500
|
||||
// @User: Standard
|
||||
|
||||
// @Param: THR_ACCEL_I
|
||||
// @Param: ACCEL_Z_I
|
||||
// @DisplayName: Throttle acceleration controller I gain
|
||||
// @Description: Throttle acceleration controller I gain. Corrects long-term difference in desired vertical acceleration and actual acceleration
|
||||
// @Range: 0.000 3.000
|
||||
// @User: Standard
|
||||
|
||||
// @Param: THR_ACCEL_IMAX
|
||||
// @Param: ACCEL_Z_IMAX
|
||||
// @DisplayName: Throttle acceleration controller I gain maximum
|
||||
// @Description: Throttle acceleration controller I gain maximum. Constrains the maximum pwm that the I term will generate
|
||||
// @Range: 0 1000
|
||||
// @Units: Percent*10
|
||||
// @User: Standard
|
||||
|
||||
// @Param: THR_ACCEL_D
|
||||
// @Param: ACCEL_Z_D
|
||||
// @DisplayName: Throttle acceleration controller D gain
|
||||
// @Description: Throttle acceleration controller D gain. Compensates for short-term change in desired vertical acceleration vs actual acceleration
|
||||
// @Range: 0.000 0.400
|
||||
// @User: Standard
|
||||
GGROUP(pid_throttle_accel,"THR_ACCEL_", AC_PID),
|
||||
GGROUP(pid_accel_z, "ACCEL_Z_", AC_PID),
|
||||
|
||||
// P controllers
|
||||
//--------------
|
||||
@ -778,19 +759,19 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GGROUP(p_stabilize_yaw, "STB_YAW_", AC_P),
|
||||
|
||||
// @Param: THR_ALT_P
|
||||
// @DisplayName: Altitude controller P gain
|
||||
// @Description: Altitude controller P gain. Converts the difference between the desired altitude and actual altitude into a climb or descent rate which is passed to the throttle rate controller
|
||||
// @Param: POS_Z_P
|
||||
// @DisplayName: Position (vertical) controller P gain
|
||||
// @Description: Position (vertical) controller P gain. Converts the difference between the desired altitude and actual altitude into a climb or descent rate which is passed to the throttle rate controller
|
||||
// @Range: 1.000 3.000
|
||||
// @User: Standard
|
||||
GGROUP(p_alt_hold, "THR_ALT_", AC_P),
|
||||
GGROUP(p_alt_hold, "POS_Z_", AC_P),
|
||||
|
||||
// @Param: HLD_LAT_P
|
||||
// @DisplayName: Loiter position controller P gain
|
||||
// @Param: POS_XY_P
|
||||
// @DisplayName: Position (horizonal) controller P gain
|
||||
// @Description: Loiter position controller P gain. Converts the distance (in the latitude direction) to the target location into a desired speed which is then passed to the loiter latitude rate controller
|
||||
// @Range: 0.500 2.000
|
||||
// @User: Standard
|
||||
GGROUP(p_loiter_pos, "HLD_LAT_", AC_P),
|
||||
GGROUP(p_pos_xy, "POS_XY_", AC_P),
|
||||
|
||||
// variables not in the g class which contain EEPROM saved variables
|
||||
|
||||
|
@ -636,8 +636,8 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Loiter position control gains
|
||||
//
|
||||
#ifndef LOITER_POS_P
|
||||
# define LOITER_POS_P 1.0f
|
||||
#ifndef POS_XY_P
|
||||
# define POS_XY_P 1.0f
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
@ -695,26 +695,26 @@
|
||||
# define ALT_HOLD_P 1.0f
|
||||
#endif
|
||||
|
||||
// RATE control
|
||||
#ifndef THROTTLE_RATE_P
|
||||
# define THROTTLE_RATE_P 5.0f
|
||||
// Velocity (vertical) control gains
|
||||
#ifndef VEL_Z_P
|
||||
# define VEL_Z_P 5.0f
|
||||
#endif
|
||||
|
||||
// Throttle Accel control
|
||||
#ifndef THROTTLE_ACCEL_P
|
||||
# define THROTTLE_ACCEL_P 0.50f
|
||||
// Accel (vertical) control gains
|
||||
#ifndef ACCEL_Z_P
|
||||
# define ACCEL_Z_P 0.50f
|
||||
#endif
|
||||
#ifndef THROTTLE_ACCEL_I
|
||||
# define THROTTLE_ACCEL_I 1.00f
|
||||
#ifndef ACCEL_Z_I
|
||||
# define ACCEL_Z_I 1.00f
|
||||
#endif
|
||||
#ifndef THROTTLE_ACCEL_D
|
||||
# define THROTTLE_ACCEL_D 0.0f
|
||||
#ifndef ACCEL_Z_D
|
||||
# define ACCEL_Z_D 0.0f
|
||||
#endif
|
||||
#ifndef THROTTLE_ACCEL_IMAX
|
||||
# define THROTTLE_ACCEL_IMAX 800
|
||||
#ifndef ACCEL_Z_IMAX
|
||||
# define ACCEL_Z_IMAX 800
|
||||
#endif
|
||||
#ifndef THROTTLE_ACCEL_FILT_HZ
|
||||
# define THROTTLE_ACCEL_FILT_HZ 20.0f
|
||||
#ifndef ACCEL_Z_FILT_HZ
|
||||
# define ACCEL_Z_FILT_HZ 20.0f
|
||||
#endif
|
||||
|
||||
// default maximum vertical velocity and acceleration the pilot may request
|
||||
|
@ -118,9 +118,9 @@
|
||||
#define CH6_YAW_RATE_KD 26 // body frame yaw rate controller's D term
|
||||
#define CH6_ALTITUDE_HOLD_KP 14 // altitude hold controller's P term (alt error to desired rate)
|
||||
#define CH6_THROTTLE_RATE_KP 7 // throttle rate controller's P term (desired rate to acceleration or motor output)
|
||||
#define CH6_THROTTLE_ACCEL_KP 34 // accel based throttle controller's P term
|
||||
#define CH6_THROTTLE_ACCEL_KI 35 // accel based throttle controller's I term
|
||||
#define CH6_THROTTLE_ACCEL_KD 36 // accel based throttle controller's D term
|
||||
#define CH6_ACCEL_Z_KP 34 // accel based throttle controller's P term
|
||||
#define CH6_ACCEL_Z_KI 35 // accel based throttle controller's I term
|
||||
#define CH6_ACCEL_Z_KD 36 // accel based throttle controller's D term
|
||||
#define CH6_LOITER_POSITION_KP 12 // loiter distance controller's P term (position error to speed)
|
||||
#define CH6_VEL_XY_KP 22 // loiter rate controller's P term (speed error to tilt angle)
|
||||
#define CH6_VEL_XY_KI 28 // loiter rate controller's I term (speed error to tilt angle)
|
||||
|
@ -59,24 +59,24 @@ static void tuning() {
|
||||
break;
|
||||
|
||||
case CH6_THROTTLE_RATE_KP:
|
||||
g.p_throttle_rate.kP(tuning_value);
|
||||
g.p_vel_z.kP(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_THROTTLE_ACCEL_KP:
|
||||
g.pid_throttle_accel.kP(tuning_value);
|
||||
case CH6_ACCEL_Z_KP:
|
||||
g.pid_accel_z.kP(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_THROTTLE_ACCEL_KI:
|
||||
g.pid_throttle_accel.kI(tuning_value);
|
||||
case CH6_ACCEL_Z_KI:
|
||||
g.pid_accel_z.kI(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_THROTTLE_ACCEL_KD:
|
||||
g.pid_throttle_accel.kD(tuning_value);
|
||||
case CH6_ACCEL_Z_KD:
|
||||
g.pid_accel_z.kD(tuning_value);
|
||||
break;
|
||||
|
||||
// Loiter and navigation tuning
|
||||
case CH6_LOITER_POSITION_KP:
|
||||
g.p_loiter_pos.kP(tuning_value);
|
||||
g.p_pos_xy.kP(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_VEL_XY_KP:
|
||||
|
Loading…
Reference in New Issue
Block a user