From 9426849b8d1d8602af4a17e66d1f303460300b15 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Mon, 5 Sep 2016 10:45:10 -0400 Subject: [PATCH] Sub: Change default ATC_ACCEL_Y_MAX to 110k cd/ss --- ArduSub/system.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index 09a0339f41..8246dcb13b 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -250,6 +250,11 @@ void Sub::init_ardupilot() //----------------------------- init_barometer(true); + // backwards compatibility + if(attitude_control.get_accel_yaw_max() < 110000.0f) { + attitude_control.save_accel_yaw_max(110000.0f); + } + // initialise rangefinder #if RANGEFINDER_ENABLED == ENABLED init_rangefinder();