mirror of https://github.com/ArduPilot/ardupilot
APM_Control: make the default time constant 0.75
thanks to Tom for the testing!
This commit is contained in:
parent
770b7b5901
commit
af2d7232c5
|
@ -32,7 +32,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] PROGMEM = {
|
|||
// @Units: seconds
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TCONST", 0, AP_SteerController, _tau, 0.5f),
|
||||
AP_GROUPINFO("TCONST", 0, AP_SteerController, _tau, 0.75f),
|
||||
|
||||
// @Param: P
|
||||
// @DisplayName: Steering turning gain
|
||||
|
|
Loading…
Reference in New Issue