mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
APM_Control: increase available range for roll and pitch
This commit is contained in:
parent
fb867f3a06
commit
8f3dad0d1c
@ -38,7 +38,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 2.0
|
||||
// @Range: 0.1 3.0
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 0.4f),
|
||||
|
@ -37,7 +37,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 2.0
|
||||
// @Range: 0.1 4.0
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("P", 1, AP_RollController, gains.P, 0.4f),
|
||||
|
Loading…
Reference in New Issue
Block a user