From f9186de0ca282824fa67ed6484f7880888aa3cd1 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 21 Jul 2017 13:16:23 +0900 Subject: [PATCH] Rover: steering mode formatting change no functional change --- APMrover2/mode_steering.cpp | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/APMrover2/mode_steering.cpp b/APMrover2/mode_steering.cpp index db01976936..a6578a7a0e 100644 --- a/APMrover2/mode_steering.cpp +++ b/APMrover2/mode_steering.cpp @@ -1,14 +1,11 @@ #include "mode.h" #include "Rover.h" -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. - */ +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. const float ground_speed = rover.ground_speed; float max_g_force = ground_speed * ground_speed / rover.steerController.get_turn_radius();