mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APM_Control: allow for a wider range of P values for roll/pitch
values above 1.0 are sometimes needed
This commit is contained in:
parent
41ba4a1ed2
commit
5901b8b22a
@ -28,7 +28,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
|
||||
// @Param: P
|
||||
// @DisplayName: Proportional Gain
|
||||
// @Description: This is the gain from pitch angle to elevator. This gain works the same way as PTCH2SRV_P in the old PID controller and can be set to the same value.
|
||||
// @Range: 0.1 1.0
|
||||
// @Range: 0.1 2.0
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("P", 1, AP_PitchController, _K_P, 0.4f),
|
||||
|
@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
|
||||
// @Param: P
|
||||
// @DisplayName: Proportional Gain
|
||||
// @Description: This is the gain from bank angle to aileron. This gain works the same way as the P term in the old PID (RLL2SRV_P) and can be set to the same value.
|
||||
// @Range: 0.1 1.0
|
||||
// @Range: 0.1 2.0
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("P", 1, AP_RollController, _K_P, 0.4f),
|
||||
|
Loading…
Reference in New Issue
Block a user