diff --git a/APMrover2/mode_steering.cpp b/APMrover2/mode_steering.cpp index 4696fe6587..ef5cb31729 100644 --- a/APMrover2/mode_steering.cpp +++ b/APMrover2/mode_steering.cpp @@ -18,7 +18,6 @@ void ModeSteering::update() // in steering mode we control lateral acceleration directly. We first calculate the maximum lateral // acceleration at full steering lock for this speed. That is V^2/R where R is the radius of turn. - // We get the radius of turn from half the STEER2SRV_P. float max_g_force = speed * speed / MAX(g2.turn_radius, 0.1f); // constrain to user set TURN_MAX_G