Browse Source

Sub: Change default ATC_ACCEL_Y_MAX to 110k cd/ss

master
Jacob Walser 9 years ago committed by Andrew Tridgell
parent
commit
9426849b8d
  1. 5
      ArduSub/system.cpp

5
ArduSub/system.cpp

@ -250,6 +250,11 @@ void Sub::init_ardupilot() @@ -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();

Loading…
Cancel
Save