Skip to content

Commit

Permalink
min_gndspd: update defaults
Browse files Browse the repository at this point in the history
  • Loading branch information
shellixyz committed Feb 16, 2025
1 parent f2c6366 commit 109a811
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1416,14 +1416,14 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Description: Minimum ground speed throttle PID I term
// @Range: 0 255
// @User: Advanced
AP_GROUPINFO("MIN_GNDSPD_I", 41, ParametersG2, mingndspd_i, 72),
AP_GROUPINFO("MIN_GNDSPD_I", 41, ParametersG2, mingndspd_i, 35),

// @Param: MIN_GNDSPD_D
// @DisplayName: Minimum ground speed throttle PID D term
// @Description: Minimum ground speed throttle PID D term
// @Range: 0 255
// @User: Advanced
AP_GROUPINFO("MIN_GNDSPD_D", 42, ParametersG2, mingndspd_d, 5),
AP_GROUPINFO("MIN_GNDSPD_D", 42, ParametersG2, mingndspd_d, 8),

// @Param: SAT_FINISHTHRESH
// @DisplayName: Number of microseconds of servo trim adjustment during 10s under which the auto trim is considered finished
Expand Down

0 comments on commit 109a811

Please sign in to comment.