From 1c3f3caf660468b8adfa60b9624d36de35b2fd5a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 26 Apr 2018 14:17:04 +0900 Subject: [PATCH] Rover: reduce TURN_MAX_G default to 0.6 --- APMrover2/Parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index c1ec62d0fc..3935b98282 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -306,7 +306,7 @@ const AP_Param::Info Rover::var_info[] = { // @Range: 0.1 10 // @Increment: 0.01 // @User: Standard - GSCALAR(turn_max_g, "TURN_MAX_G", 1.0f), + GSCALAR(turn_max_g, "TURN_MAX_G", 0.6f), // variables not in the g class which contain EEPROM saved variables