APMRover2: Steering fix style

This commit is contained in:
Pierre Kancir 2017-01-16 10:18:55 +01:00 committed by Grant Morphett
parent 363574244b
commit e0a3caea13
1 changed files with 32 additions and 32 deletions

View File

@ -299,8 +299,8 @@ void Rover::set_servos(void) {
motor1 = throttle + 0.5*steering motor1 = throttle + 0.5*steering
motor2 = throttle - 0.5*steering motor2 = throttle - 0.5*steering
*/ */
float steering_scaled = SRV_Channels::get_output_norm(SRV_Channel::k_steering); const float steering_scaled = SRV_Channels::get_output_norm(SRV_Channel::k_steering);
float throttle_scaled = SRV_Channels::get_output_norm(SRV_Channel::k_throttle); const float throttle_scaled = SRV_Channels::get_output_norm(SRV_Channel::k_throttle);
float motor1 = throttle_scaled + 0.5f * steering_scaled; float motor1 = throttle_scaled + 0.5f * steering_scaled;
float motor2 = throttle_scaled - 0.5f * steering_scaled; float motor2 = throttle_scaled - 0.5f * steering_scaled;
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, 4500 * motor1); SRV_Channels::set_output_scaled(SRV_Channel::k_steering, 4500 * motor1);