Rover: steering mode formatting change

no functional change
This commit is contained in:
Randy Mackay 2017-07-21 13:16:23 +09:00
parent 7c2c780333
commit f9186de0ca
1 changed files with 5 additions and 8 deletions

View File

@ -1,14 +1,11 @@
#include "mode.h" #include "mode.h"
#include "Rover.h" #include "Rover.h"
void ModeSteering::update() { void ModeSteering::update()
/* {
in steering mode we control lateral acceleration // in steering mode we control lateral acceleration directly. We first calculate the maximum lateral
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.
acceleration at full steering lock for this speed. That is // We get the radius of turn from half the STEER2SRV_P.
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; const float ground_speed = rover.ground_speed;
float max_g_force = ground_speed * ground_speed / rover.steerController.get_turn_radius(); float max_g_force = ground_speed * ground_speed / rover.steerController.get_turn_radius();