APM_Control: make the default time constant 0.75

thanks to Tom for the testing!
This commit is contained in:
Andrew Tridgell 2013-09-24 07:37:12 +10:00
parent 770b7b5901
commit af2d7232c5
1 changed files with 1 additions and 1 deletions

View File

@ -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