mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: Support PD Max
This commit is contained in:
parent
9f0c119c33
commit
d2549ecc68
|
@ -379,6 +379,14 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @Increment: 0.5
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: PITCH2SRV_PDMX
|
||||
// @DisplayName: Pitch axis controller PD sum maximum
|
||||
// @Description: Pitch axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||
// @Range: 0 4000
|
||||
// @Increment: 10
|
||||
// @Units: d%
|
||||
// @User: Advanced
|
||||
|
||||
GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),
|
||||
|
||||
// @Param: YAW2SRV_P
|
||||
|
@ -448,6 +456,14 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @Increment: 0.5
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: YAW2SRV_PDMX
|
||||
// @DisplayName: Yaw axis controller PD sum maximum
|
||||
// @Description: Yaw axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
|
||||
// @Range: 0 4000
|
||||
// @Increment: 10
|
||||
// @Units: d%
|
||||
// @User: Advanced
|
||||
|
||||
GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
|
|
Loading…
Reference in New Issue