mirror of https://github.com/ArduPilot/ardupilot
Plane: quadplane velocity pi moves to position control library
This commit is contained in:
parent
cef50d8a30
commit
017e71a748
|
@ -45,29 +45,6 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||
// @User: Standard
|
||||
AP_SUBGROUPINFO(p_pos_xy, "PXY_", 13, QuadPlane, AC_P),
|
||||
|
||||
// @Param: VXY_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: VXY_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: VXY_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
|
||||
AP_SUBGROUPINFO(pi_vel_xy, "VXY_", 14, QuadPlane, AC_PI_2D),
|
||||
|
||||
// @Param: VZ_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
|
||||
|
@ -595,8 +572,7 @@ bool QuadPlane::setup(void)
|
|||
}
|
||||
AP_Param::load_object_from_eeprom(attitude_control, attitude_control->var_info);
|
||||
pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control,
|
||||
p_alt_hold, p_vel_z, pid_accel_z,
|
||||
p_pos_xy, pi_vel_xy);
|
||||
p_alt_hold, p_vel_z, pid_accel_z, p_pos_xy);
|
||||
if (!pos_control) {
|
||||
hal.console->printf("%s pos_control\n", strUnableToAllocate);
|
||||
goto failed;
|
||||
|
@ -2168,7 +2144,7 @@ bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd)
|
|||
attitude_control->get_rate_pitch_pid().reset_I();
|
||||
attitude_control->get_rate_yaw_pid().reset_I();
|
||||
pid_accel_z.reset_I();
|
||||
pi_vel_xy.reset_I();
|
||||
pos_control->get_vel_xy_pid().reset_I();
|
||||
|
||||
plane.set_next_WP(cmd.content.location);
|
||||
// initially aim for current altitude
|
||||
|
|
|
@ -135,7 +135,6 @@ private:
|
|||
AC_P p_alt_hold{1};
|
||||
AC_P p_vel_z{5};
|
||||
AC_PID pid_accel_z{0.3, 1, 0, 800, 10, 0.02};
|
||||
AC_PI_2D pi_vel_xy{0.7, 0.35, 1000, 5, 0.02};
|
||||
|
||||
AP_Int8 frame_class;
|
||||
AP_Int8 frame_type;
|
||||
|
|
|
@ -149,10 +149,10 @@ AP_Float *AP_Tuning_Plane::get_param_pointer(uint8_t parm)
|
|||
return &plane.quadplane.p_alt_hold.kP();
|
||||
|
||||
case TUNING_VXY_P:
|
||||
return &plane.quadplane.pi_vel_xy.kP();
|
||||
return &plane.quadplane.pos_control->get_vel_xy_pid().kP();
|
||||
|
||||
case TUNING_VXY_I:
|
||||
return &plane.quadplane.pi_vel_xy.kI();
|
||||
return &plane.quadplane.pos_control->get_vel_xy_pid().kI();
|
||||
|
||||
case TUNING_VZ_P:
|
||||
return &plane.quadplane.p_vel_z.kP();
|
||||
|
|
Loading…
Reference in New Issue