mirror of https://github.com/ArduPilot/ardupilot
62 lines
1.8 KiB
C++
62 lines
1.8 KiB
C++
#pragma once
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
#include <AP_Vehicle/AP_Vehicle.h>
|
|
#include "AP_AutoTune.h"
|
|
#include <AP_Logger/AP_Logger.h>
|
|
#include <AP_Math/AP_Math.h>
|
|
#include <AC_PID/AC_PID.h>
|
|
|
|
class AP_PitchController {
|
|
public:
|
|
AP_PitchController(const AP_Vehicle::FixedWing &parms);
|
|
|
|
/* Do not allow copies */
|
|
AP_PitchController(const AP_PitchController &other) = delete;
|
|
AP_PitchController &operator=(const AP_PitchController&) = delete;
|
|
|
|
float get_rate_out(float desired_rate, float scaler);
|
|
float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode);
|
|
|
|
void reset_I();
|
|
|
|
/*
|
|
reduce the integrator, used when we have a low scale factor in a quadplane hover
|
|
*/
|
|
void decay_I() {
|
|
// this reduces integrator by 95% over 2s
|
|
_pid_info.I *= 0.995f;
|
|
rate_pid.set_integrator(rate_pid.get_i() * 0.995);
|
|
}
|
|
|
|
void autotune_start(void);
|
|
void autotune_restore(void);
|
|
|
|
const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; }
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
AP_Float &kP(void) { return rate_pid.kP(); }
|
|
AP_Float &kI(void) { return rate_pid.kI(); }
|
|
AP_Float &kD(void) { return rate_pid.kD(); }
|
|
AP_Float &kFF(void) { return rate_pid.ff(); }
|
|
|
|
void convert_pid();
|
|
|
|
private:
|
|
const AP_Vehicle::FixedWing &aparm;
|
|
AP_AutoTune::ATGains gains;
|
|
AP_AutoTune *autotune;
|
|
bool failed_autotune_alloc;
|
|
AP_Int16 _max_rate_neg;
|
|
AP_Float _roll_ff;
|
|
float _last_out;
|
|
AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 3, 0, 12, 0.02, 150, 1};
|
|
float angle_err_deg;
|
|
|
|
AP_Logger::PID_Info _pid_info;
|
|
|
|
float _get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode);
|
|
float _get_coordination_rate_offset(float &aspeed, bool &inverted) const;
|
|
};
|