Rover: constify some temporary variables

This commit is contained in:
Randy Mackay 2017-12-06 10:37:31 +09:00
parent 7b637334f4
commit 8f08f5189a

View File

@ -17,13 +17,13 @@ void ModeAcro::update()
get_pilot_desired_steering_and_throttle(desired_steering, desired_throttle);
// convert pilot throttle input to desired speed (up to twice the cruise speed)
float target_speed = desired_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);
const float target_speed = desired_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);
// convert pilot steering input to desired turn rate in radians/sec
float target_turn_rate = (desired_steering / 4500.0f) * radians(g2.acro_turn_rate);
const float target_turn_rate = (desired_steering / 4500.0f) * radians(g2.acro_turn_rate);
// determine if pilot is requesting pivot turn
bool is_pivot_turning = g2.motors.have_skid_steering() && is_zero(target_speed) && (!is_zero(desired_steering));
const bool is_pivot_turning = g2.motors.have_skid_steering() && is_zero(target_speed) && (!is_zero(desired_steering));
// stop vehicle if target speed is zero and not pivot turning
if (is_zero(target_speed) && !is_pivot_turning) {
@ -32,11 +32,11 @@ void ModeAcro::update()
}
// set reverse flag backing up
bool reversed = is_negative(target_speed);
const bool reversed = is_negative(target_speed);
rover.set_reverse(reversed);
// run steering turn rate controller and throttle controller
float steering_out = attitude_control.get_steering_out_rate(target_turn_rate, g2.motors.have_skid_steering(), g2.motors.limit.steer_left, g2.motors.limit.steer_right, reversed);
const float steering_out = attitude_control.get_steering_out_rate(target_turn_rate, g2.motors.have_skid_steering(), g2.motors.limit.steer_left, g2.motors.limit.steer_right, reversed);
g2.motors.set_steering(steering_out * 4500.0f);
calc_throttle(target_speed, false);
}