diff --git a/Rover/mode_acro.cpp b/Rover/mode_acro.cpp index 7e1e589402..5379be5fe4 100644 --- a/Rover/mode_acro.cpp +++ b/Rover/mode_acro.cpp @@ -9,6 +9,12 @@ void ModeAcro::update() float desired_throttle; // convert pilot stick input into desired steering and throttle get_pilot_desired_steering_and_throttle(desired_steering, desired_throttle); + + // if vehicle is balance bot, calculate actual throttle required for balancing + if (rover.is_balancebot()) { + rover.balancebot_pitch_control(desired_throttle); + } + // no valid speed, just use the provided throttle g2.motors.set_throttle(desired_throttle); } else {