ardupilot/libraries/APM_Control/AP_RollController.h

62 lines
1.7 KiB
C
Raw Normal View History

#pragma once
#include <AP_AHRS/AP_AHRS.h>
#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>
class AP_RollController {
public:
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
: aparm(parms)
, autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms)
, _ahrs(ahrs)
{
AP_Param::setup_object_defaults(this, var_info);
2017-08-30 15:10:44 -03:00
}
/* Do not allow copies */
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);
void reset_I();
void autotune_start(void) { autotune.start(); }
void autotune_restore(void) { autotune.stop(); }
const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; }
static const struct AP_Param::GroupInfo var_info[];
2016-04-16 07:37:33 -03:00
// tuning accessors
void kP(float v) { gains.P.set(v); }
void kI(float v) { gains.I.set(v); }
void kD(float v) { gains.D.set(v); }
void kFF(float v) { gains.FF.set(v); }
AP_Float &kP(void) { return gains.P; }
AP_Float &kI(void) { return gains.I; }
AP_Float &kD(void) { return gains.D; }
AP_Float &kFF(void) { return gains.FF; }
2017-08-30 15:10:44 -03:00
private:
2017-08-30 15:10:44 -03:00
const AP_Vehicle::FixedWing &aparm;
AP_AutoTune::ATGains gains;
AP_AutoTune autotune;
uint32_t _last_t;
float _last_out;
AP_Logger::PID_Info _pid_info;
int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator);
AP_AHRS &_ahrs;
};