mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: added SMAX param docs
This commit is contained in:
parent
9a244eef29
commit
999c7e0dc4
|
@ -355,7 +355,15 @@ const AP_Param::Info Tracker::var_info[] = {
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),
|
|
||||||
|
// @Param: PITCH2SRV_SMAX
|
||||||
|
// @DisplayName: Pitch slew rate limit
|
||||||
|
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
|
||||||
|
// @Range: 0 200
|
||||||
|
// @Increment: 0.5
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
|
GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),
|
||||||
|
|
||||||
// @Param: YAW2SRV_P
|
// @Param: YAW2SRV_P
|
||||||
// @DisplayName: Yaw axis controller P gain
|
// @DisplayName: Yaw axis controller P gain
|
||||||
|
@ -416,7 +424,15 @@ const AP_Param::Info Tracker::var_info[] = {
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),
|
|
||||||
|
// @Param: YAW2SRV_SMAX
|
||||||
|
// @DisplayName: Yaw slew rate limit
|
||||||
|
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
|
||||||
|
// @Range: 0 200
|
||||||
|
// @Increment: 0.5
|
||||||
|
// @User: Advanced
|
||||||
|
|
||||||
|
GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),
|
||||||
|
|
||||||
#ifdef ENABLE_SCRIPTING
|
#ifdef ENABLE_SCRIPTING
|
||||||
// @Group: SCR_
|
// @Group: SCR_
|
||||||
|
|
Loading…
Reference in New Issue