2017-07-18 23:17:45 -03:00
|
|
|
#include "mode.h"
|
|
|
|
#include "Rover.h"
|
|
|
|
|
2017-07-21 01:16:23 -03:00
|
|
|
void ModeSteering::update()
|
|
|
|
{
|
2017-08-08 21:24:30 -03:00
|
|
|
// get speed forward
|
|
|
|
float speed;
|
|
|
|
if (!attitude_control.get_forward_speed(speed)) {
|
2017-08-10 00:06:43 -03:00
|
|
|
// no valid speed so stop
|
2017-08-15 22:32:56 -03:00
|
|
|
g2.motors.set_throttle(0.0f);
|
2017-08-08 21:24:30 -03:00
|
|
|
g2.motors.set_steering(0.0f);
|
|
|
|
return;
|
|
|
|
}
|
2017-07-21 01:17:19 -03:00
|
|
|
|
2018-05-05 22:48:26 -03:00
|
|
|
float desired_steering, desired_speed;
|
|
|
|
get_pilot_desired_steering_and_speed(desired_steering, desired_speed);
|
|
|
|
|
2018-05-06 02:28:54 -03:00
|
|
|
bool reversed = is_negative(desired_speed);
|
|
|
|
|
2017-11-13 17:13:03 -04:00
|
|
|
// determine if pilot is requesting pivot turn
|
2018-05-06 02:28:54 -03:00
|
|
|
if (g2.motors.have_skid_steering() && is_zero(desired_speed)) {
|
|
|
|
// pivot turning using turn rate controller
|
|
|
|
// convert pilot steering input to desired turn rate in radians/sec
|
|
|
|
const float target_turn_rate = (desired_steering / 4500.0f) * radians(g2.acro_turn_rate);
|
|
|
|
|
|
|
|
// run steering turn rate controller and throttle controller
|
|
|
|
const float steering_out = attitude_control.get_steering_out_rate(target_turn_rate,
|
|
|
|
g2.motors.limit.steer_left,
|
2018-05-21 22:05:20 -03:00
|
|
|
g2.motors.limit.steer_right,
|
|
|
|
rover.G_Dt);
|
2018-05-06 02:28:54 -03:00
|
|
|
g2.motors.set_steering(steering_out * 4500.0f);
|
2017-11-13 17:13:03 -04:00
|
|
|
} else {
|
2018-05-06 02:28:54 -03:00
|
|
|
// In steering mode we control lateral acceleration directly.
|
|
|
|
// For regular steering vehicles we use the maximum lateral acceleration
|
|
|
|
// at full steering lock for this speed: V^2/R where R is the radius of turn.
|
|
|
|
float max_g_force = speed * speed / MAX(g2.turn_radius, 0.1f);
|
|
|
|
max_g_force = constrain_float(max_g_force, 0.1f, g.turn_max_g * GRAVITY_MSS);
|
|
|
|
|
|
|
|
// convert pilot steering input to desired lateral acceleration
|
|
|
|
float desired_lat_accel = max_g_force * (desired_steering / 4500.0f);
|
|
|
|
|
|
|
|
// reverse target lateral acceleration if backing up
|
|
|
|
if (reversed) {
|
|
|
|
desired_lat_accel = -desired_lat_accel;
|
|
|
|
}
|
|
|
|
|
|
|
|
// run lateral acceleration to steering controller
|
|
|
|
calc_steering_from_lateral_acceleration(desired_lat_accel, reversed);
|
2017-07-21 01:17:19 -03:00
|
|
|
}
|
2017-07-18 23:17:45 -03:00
|
|
|
|
2018-02-18 21:29:49 -04:00
|
|
|
// run speed to throttle controller
|
2018-05-05 22:48:26 -03:00
|
|
|
calc_throttle(desired_speed, false, true);
|
2017-07-18 23:17:45 -03:00
|
|
|
}
|