AP_PitchController: return floats

This commit is contained in:
Iampete1 2021-09-18 18:57:51 +01:00 committed by Andrew Tridgell
parent 6e4ae3898d
commit da4fd7a914
2 changed files with 7 additions and 7 deletions

View File

@ -144,7 +144,7 @@ AP_PitchController::AP_PitchController(const AP_Vehicle::FixedWing &parms)
/*
AC_PID based rate controller
*/
int32_t AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed)
float AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed)
{
const float dt = AP::scheduler().get_loop_period_s();
@ -209,7 +209,7 @@ int32_t AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool
}
// output is scaled to notional centidegrees of deflection
return constrain_int32(out * 100, -4500, 4500);
return constrain_float(out * 100, -4500, 4500);
}
/*
@ -222,7 +222,7 @@ int32_t AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool
4) minimum FBW airspeed (metres/sec)
5) maximum FBW airspeed (metres/sec)
*/
int32_t AP_PitchController::get_rate_out(float desired_rate, float scaler)
float AP_PitchController::get_rate_out(float desired_rate, float scaler)
{
float aspeed;
if (!AP::ahrs().airspeed_estimate(aspeed)) {
@ -282,7 +282,7 @@ float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inv
// 4) minimum FBW airspeed (metres/sec)
// 5) maximum FBW airspeed (metres/sec)
//
int32_t AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
{
// Calculate offset to pitch rate demand required to maintain pitch angle whilst banking
// Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn

View File

@ -15,8 +15,8 @@ public:
AP_PitchController(const AP_PitchController &other) = delete;
AP_PitchController &operator=(const AP_PitchController&) = delete;
int32_t get_rate_out(float desired_rate, float scaler);
int32_t get_servo_out(int32_t angle_err, float scaler, bool disable_integrator);
float get_rate_out(float desired_rate, float scaler);
float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator);
void reset_I();
@ -56,6 +56,6 @@ private:
AP_Logger::PID_Info _pid_info;
int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed);
float _get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed);
float _get_coordination_rate_offset(float &aspeed, bool &inverted) const;
};