Skip to content

Commit

Permalink
Rover: fix two-paddle input decoding
Browse files Browse the repository at this point in the history
steering output was twice what it should be.  full steering (i.e. 4500 or -4500) should occur when one paddle is up and the other is completely down
  • Loading branch information
rmackay9 committed Mar 12, 2018
1 parent 1dd14a8 commit e3f7011
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion APMrover2/mode.cpp
Expand Up @@ -76,7 +76,7 @@ void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &t
throttle_out = 0.5f * (left_paddle + right_paddle) * 100.0f;

const float steering_dir = is_negative(throttle_out) ? -1 : 1;
steering_out = steering_dir * (left_paddle - right_paddle) * 4500.0f;
steering_out = steering_dir * (left_paddle - right_paddle) * 0.5f * 4500.0f;
break;
}

Expand Down

0 comments on commit e3f7011

Please sign in to comment.