From 47848f07fa71366c7c4ce41c09641736d9bcc021 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 7 Nov 2022 20:02:32 +0900 Subject: [PATCH] Rover: balance bot max pitch default to 10deg --- Rover/Parameters.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 19d755afd8..866065b72f 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -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