mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APM_Control: Support PD Max
This commit is contained in:
parent
8068f72be3
commit
029950ef05
@ -131,6 +131,13 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
|
|||||||
// @Increment: 0.5
|
// @Increment: 0.5
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: _RATE_PDMX
|
||||||
|
// @DisplayName: Pitch axis rate controller PD sum maximum
|
||||||
|
// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||||
|
// @Range: 0 1
|
||||||
|
// @Increment: 0.01
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID),
|
AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
@ -114,6 +114,13 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
|
|||||||
// @Increment: 0.5
|
// @Increment: 0.5
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: _RATE_PDMX
|
||||||
|
// @DisplayName: Roll axis rate controller PD sum maximum
|
||||||
|
// @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||||
|
// @Range: 0 1
|
||||||
|
// @Increment: 0.01
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_RollController, AC_PID),
|
AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_RollController, AC_PID),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
@ -145,6 +145,13 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = {
|
|||||||
// @Increment: 0.5
|
// @Increment: 0.5
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: _RATE_PDMX
|
||||||
|
// @DisplayName: Yaw axis rate controller PD sum maximum
|
||||||
|
// @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||||
|
// @Range: 0 1
|
||||||
|
// @Increment: 0.01
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_YawController, AC_PID),
|
AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_YawController, AC_PID),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
@ -141,6 +141,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Increment: 0.5
|
// @Increment: 0.5
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: _STR_RAT_PDMX
|
||||||
|
// @DisplayName: Steering control PD sum maximum
|
||||||
|
// @Description: Steering control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||||
|
// @Range: 0.000 1.000
|
||||||
|
// @Increment: 0.01
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID),
|
AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID),
|
||||||
|
|
||||||
// @Param: _SPEED_P
|
// @Param: _SPEED_P
|
||||||
@ -217,6 +224,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Increment: 0.5
|
// @Increment: 0.5
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: _SPEED_PDMX
|
||||||
|
// @DisplayName: Speed control PD sum maximum
|
||||||
|
// @Description: Speed control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||||
|
// @Range: 0.000 1.000
|
||||||
|
// @Increment: 0.01
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID),
|
AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID),
|
||||||
|
|
||||||
// @Param: _ACCEL_MAX
|
// @Param: _ACCEL_MAX
|
||||||
@ -353,6 +367,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Increment: 0.5
|
// @Increment: 0.5
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: _BAL_PDMX
|
||||||
|
// @DisplayName: Pitch control PD sum maximum
|
||||||
|
// @Description: Pitch control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||||
|
// @Range: 0.000 1.000
|
||||||
|
// @Increment: 0.01
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID),
|
AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID),
|
||||||
|
|
||||||
// @Param: _BAL_PIT_FF
|
// @Param: _BAL_PIT_FF
|
||||||
@ -437,6 +458,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Increment: 0.5
|
// @Increment: 0.5
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: _SAIL_PDMX
|
||||||
|
// @DisplayName: Sail Heel control PD sum maximum
|
||||||
|
// @Description: Sail Heel control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||||
|
// @Range: 0.000 1.000
|
||||||
|
// @Increment: 0.01
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID),
|
AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID),
|
||||||
|
|
||||||
// @Param: _TURN_MAX_G
|
// @Param: _TURN_MAX_G
|
||||||
|
Loading…
Reference in New Issue
Block a user