#include<stdio.h>1#include "Rover.h"23// Function to set a desired pitch angle according to throttle4void Rover::balancebot_pitch_control(float &throttle)5{6// calculate desired pitch angle7const float demanded_pitch = radians(-throttle * 0.01f * g2.bal_pitch_max) + radians(g2.bal_pitch_trim);89// calculate required throttle using PID controller10throttle = g2.attitude_control.get_throttle_out_from_pitch(demanded_pitch, radians(g2.bal_pitch_max), g2.motors.limit.throttle_lower || g2.motors.limit.throttle_upper, G_Dt) * 100.0f;11}1213// returns true if vehicle is a balance bot14// called in AP_MotorsUGV::output()15// this affects whether the vehicle tries to control its pitch with throttle output16bool Rover::is_balancebot() const17{18return ((enum frame_class)g2.frame_class.get() == FRAME_BALANCEBOT);19}202122