mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
APM_Control: raised default PID gains for roll/pitch
This commit is contained in:
parent
5ba6f5a3a2
commit
6fe07e5702
@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
|
||||
// @Range: 0.1 3.0
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 0.6f),
|
||||
AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 1.0f),
|
||||
|
||||
// @Param: D
|
||||
// @DisplayName: Damping Gain
|
||||
@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
|
||||
// @Range: 0 0.1
|
||||
// @Increment: 0.01
|
||||
// @User: User
|
||||
AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.02f),
|
||||
AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.08f),
|
||||
|
||||
// @Param: I
|
||||
// @DisplayName: Integrator Gain
|
||||
@ -54,7 +54,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
|
||||
// @Range: 0 0.5
|
||||
// @Increment: 0.05
|
||||
// @User: User
|
||||
AP_GROUPINFO("I", 3, AP_PitchController, gains.I, 0.15f),
|
||||
AP_GROUPINFO("I", 3, AP_PitchController, gains.I, 0.3f),
|
||||
|
||||
// @Param: RMAX_UP
|
||||
// @DisplayName: Pitch up max rate
|
||||
|
@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
|
||||
// @Range: 0.1 4.0
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("P", 1, AP_RollController, gains.P, 0.6f),
|
||||
AP_GROUPINFO("P", 1, AP_RollController, gains.P, 1.0f),
|
||||
|
||||
// @Param: D
|
||||
// @DisplayName: Damping Gain
|
||||
@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
|
||||
// @Range: 0 0.1
|
||||
// @Increment: 0.01
|
||||
// @User: User
|
||||
AP_GROUPINFO("D", 2, AP_RollController, gains.D, 0.02f),
|
||||
AP_GROUPINFO("D", 2, AP_RollController, gains.D, 0.08f),
|
||||
|
||||
// @Param: I
|
||||
// @DisplayName: Integrator Gain
|
||||
@ -54,7 +54,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
|
||||
// @Range: 0 1.0
|
||||
// @Increment: 0.05
|
||||
// @User: User
|
||||
AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.1f),
|
||||
AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.3f),
|
||||
|
||||
// @Param: RMAX
|
||||
// @DisplayName: Maximum Roll Rate
|
||||
|
Loading…
Reference in New Issue
Block a user