From a79ad5489c307020ba1c0c15959c3a4880778986 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 15 Mar 2022 20:07:13 +0900 Subject: [PATCH] Rover: balance bot stands in acro with no position estimate --- Rover/mode_acro.cpp | 6 ++++++ 1 file changed, 6 insertions(+) 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 {