mirror of https://github.com/ArduPilot/ardupilot
Copter: velocity pi moved to position control library
This commit is contained in:
parent
00037fd50e
commit
6546ccbb3f
|
@ -48,10 +48,11 @@
|
|||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||
#include <AP_NavEKF3/AP_NavEKF3.h>
|
||||
#include <AP_Mission/AP_Mission.h> // Mission command library
|
||||
#include <AC_PID/AC_PID.h> // PID library
|
||||
#include <AC_PID/AC_PI_2D.h> // PID library (2-axis)
|
||||
#include <AC_PID/AC_HELI_PID.h> // Heli specific Rate PID library
|
||||
#include <AC_PID/AC_P.h> // P library
|
||||
#include <AC_PID/AC_PID.h> // PID library
|
||||
#include <AC_PID/AC_PI_2D.h> // PI library (2-axis)
|
||||
#include <AC_PID/AC_PID_2D.h> // PID library (2-axis)
|
||||
#include <AC_PID/AC_HELI_PID.h> // Heli specific Rate PID library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter
|
||||
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
|
||||
|
|
|
@ -555,29 +555,6 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @User: Advanced
|
||||
GSCALAR(acro_rp_expo, "ACRO_RP_EXPO", ACRO_RP_EXPO_DEFAULT),
|
||||
|
||||
// @Param: VEL_XY_P
|
||||
// @DisplayName: Velocity (horizontal) P gain
|
||||
// @Description: Velocity (horizontal) P gain. Converts the difference between desired velocity to a target acceleration
|
||||
// @Range: 0.1 6.0
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: VEL_XY_I
|
||||
// @DisplayName: Velocity (horizontal) I gain
|
||||
// @Description: Velocity (horizontal) I gain. Corrects long-term difference in desired velocity to a target acceleration
|
||||
// @Range: 0.02 1.00
|
||||
// @Increment: 0.01
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: VEL_XY_IMAX
|
||||
// @DisplayName: Velocity (horizontal) integrator maximum
|
||||
// @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
|
||||
// @Range: 0 4500
|
||||
// @Increment: 10
|
||||
// @Units: cm/s/s
|
||||
// @User: Advanced
|
||||
GGROUP(pi_vel_xy, "VEL_XY_", AC_PI_2D),
|
||||
|
||||
// @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
|
||||
|
@ -1142,7 +1119,11 @@ void Copter::convert_pid_parameters(void)
|
|||
{ Parameters::k_param_p_stabilize_yaw, 0, AP_PARAM_FLOAT, "ATC_ANG_YAW_P" },
|
||||
{ Parameters::k_param_pid_rate_roll, 6, AP_PARAM_FLOAT, "ATC_RAT_RLL_FILT" },
|
||||
{ Parameters::k_param_pid_rate_pitch, 6, AP_PARAM_FLOAT, "ATC_RAT_PIT_FILT" },
|
||||
{ Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" }
|
||||
{ Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" },
|
||||
{ Parameters::k_param_pi_vel_xy, 0, AP_PARAM_FLOAT, "PSC_VELXY_P" },
|
||||
{ Parameters::k_param_pi_vel_xy, 1, AP_PARAM_FLOAT, "PSC_VELXY_I" },
|
||||
{ Parameters::k_param_pi_vel_xy, 2, AP_PARAM_FLOAT, "PSC_VELXY_IMAX" },
|
||||
{ Parameters::k_param_pi_vel_xy, 3, AP_PARAM_FLOAT, "PSC_VELXY_FILT" },
|
||||
};
|
||||
const AP_Param::ConversionInfo throttle_conversion_info[] = {
|
||||
{ Parameters::k_param_throttle_min, 0, AP_PARAM_FLOAT, "MOT_SPIN_MIN" },
|
||||
|
|
|
@ -358,7 +358,7 @@ public:
|
|||
k_param_acro_yaw_p,
|
||||
k_param_autotune_axis_bitmask,
|
||||
k_param_autotune_aggressiveness,
|
||||
k_param_pi_vel_xy,
|
||||
k_param_pi_vel_xy, // remove
|
||||
k_param_fs_ekf_action,
|
||||
k_param_rtl_climb_min,
|
||||
k_param_rpm_sensor,
|
||||
|
@ -469,8 +469,6 @@ public:
|
|||
AP_Float acro_rp_expo;
|
||||
|
||||
// PI/D controllers
|
||||
AC_PI_2D pi_vel_xy;
|
||||
|
||||
AC_P p_vel_z;
|
||||
AC_PID pid_accel_z;
|
||||
|
||||
|
@ -487,8 +485,6 @@ public:
|
|||
Parameters() :
|
||||
// PID controller initial P initial I initial D initial imax initial filt hz pid rate
|
||||
//---------------------------------------------------------------------------------------------------------------------------------
|
||||
pi_vel_xy (VEL_XY_P, VEL_XY_I, VEL_XY_IMAX, VEL_XY_FILT_HZ, WPNAV_LOITER_UPDATE_TIME),
|
||||
|
||||
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, 0),
|
||||
|
||||
|
|
|
@ -477,22 +477,6 @@
|
|||
# define BRAKE_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Brake Mode
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Velocity (horizontal) gains
|
||||
//
|
||||
#ifndef VEL_XY_P
|
||||
# define VEL_XY_P 1.0f
|
||||
#endif
|
||||
#ifndef VEL_XY_I
|
||||
# define VEL_XY_I 0.5f
|
||||
#endif
|
||||
#ifndef VEL_XY_IMAX
|
||||
# define VEL_XY_IMAX 1000
|
||||
#endif
|
||||
#ifndef VEL_XY_FILT_HZ
|
||||
# define VEL_XY_FILT_HZ 5.0f
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// PosHold parameter defaults
|
||||
//
|
||||
|
|
|
@ -599,7 +599,7 @@ void Copter::allocate_motors(void)
|
|||
|
||||
pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control,
|
||||
g.p_alt_hold, g.p_vel_z, g.pid_accel_z,
|
||||
g.p_pos_xy, g.pi_vel_xy);
|
||||
g.p_pos_xy);
|
||||
if (pos_control == nullptr) {
|
||||
AP_HAL::panic("Unable to allocate PosControl");
|
||||
}
|
||||
|
|
|
@ -88,11 +88,11 @@ void Copter::tuning() {
|
|||
break;
|
||||
|
||||
case TUNING_VEL_XY_KP:
|
||||
g.pi_vel_xy.kP(tuning_value);
|
||||
pos_control->get_vel_xy_pid().kP(tuning_value);
|
||||
break;
|
||||
|
||||
case TUNING_VEL_XY_KI:
|
||||
g.pi_vel_xy.kI(tuning_value);
|
||||
pos_control->get_vel_xy_pid().kI(tuning_value);
|
||||
break;
|
||||
|
||||
case TUNING_WP_SPEED:
|
||||
|
|
Loading…
Reference in New Issue