mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_RollController: return floats
This commit is contained in:
parent
da4fd7a914
commit
a590a675d6
@ -129,7 +129,7 @@ AP_RollController::AP_RollController(const AP_Vehicle::FixedWing &parms)
|
||||
/*
|
||||
AC_PID based rate controller
|
||||
*/
|
||||
int32_t AP_RollController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator)
|
||||
float AP_RollController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator)
|
||||
{
|
||||
const AP_AHRS &_ahrs = AP::ahrs();
|
||||
|
||||
@ -197,7 +197,7 @@ int32_t AP_RollController::_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);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -207,7 +207,7 @@ int32_t AP_RollController::_get_rate_out(float desired_rate, float scaler, bool
|
||||
1) desired roll rate in degrees/sec
|
||||
2) control gain scaler = scaling_speed / aspeed
|
||||
*/
|
||||
int32_t AP_RollController::get_rate_out(float desired_rate, float scaler)
|
||||
float AP_RollController::get_rate_out(float desired_rate, float scaler)
|
||||
{
|
||||
return _get_rate_out(desired_rate, scaler, false);
|
||||
}
|
||||
@ -221,7 +221,7 @@ int32_t AP_RollController::get_rate_out(float desired_rate, float scaler)
|
||||
3) boolean which is true when stabilise mode is active
|
||||
4) minimum FBW airspeed (metres/sec)
|
||||
*/
|
||||
int32_t AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
|
||||
float AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
|
||||
{
|
||||
if (gains.tau < 0.05f) {
|
||||
gains.tau.set(0.05f);
|
||||
|
@ -15,8 +15,8 @@ public:
|
||||
AP_RollController(const AP_RollController &other) = delete;
|
||||
AP_RollController &operator=(const AP_RollController&) = 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();
|
||||
|
||||
@ -61,5 +61,5 @@ private:
|
||||
|
||||
AP_Logger::PID_Info _pid_info;
|
||||
|
||||
int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator);
|
||||
float _get_rate_out(float desired_rate, float scaler, bool disable_integrator);
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user