mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Blimp: Support PD Max
This commit is contained in:
parent
029950ef05
commit
9f0c119c33
@ -721,6 +721,14 @@ const AP_Param::Info Blimp::var_info[] = {
|
|||||||
// @Range: 0 200
|
// @Range: 0 200
|
||||||
// @Increment: 0.5
|
// @Increment: 0.5
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
|
||||||
|
// @Param: POSYAW_PDMX
|
||||||
|
// @DisplayName: Position (yaw) axis controller PD sum maximum
|
||||||
|
// @Description: Position (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
|
||||||
GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID),
|
GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID),
|
||||||
|
|
||||||
// @Group:
|
// @Group:
|
||||||
|
Loading…
Reference in New Issue
Block a user