Rover: balance bot max pitch default to 10deg

This commit is contained in:
Randy Mackay 2022-11-07 20:02:32 +09:00
parent 43dd733084
commit 46c9eea17f
1 changed files with 2 additions and 2 deletions

View File

@ -500,10 +500,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @DisplayName: BalanceBot Maximum Pitch
// @Description: Pitch angle in degrees at 100% throttle
// @Units: deg
// @Range: 0 5
// @Range: 0 15
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 2),
AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 10),
// @Param: CRASH_ANGLE
// @DisplayName: Crash Angle