APM:Libraries
AP_RollController.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_AHRS/AP_AHRS.h>
4 #include <AP_Common/AP_Common.h>
6 #include "AP_AutoTune.h"
7 #include <DataFlash/DataFlash.h>
8 #include <AP_Math/AP_Math.h>
9 
11 public:
13  : aparm(parms)
14  , autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash)
15  , _ahrs(ahrs)
16  {
18  }
19 
20  /* Do not allow copies */
21  AP_RollController(const AP_RollController &other) = delete;
23 
24  int32_t get_rate_out(float desired_rate, float scaler);
25  int32_t get_servo_out(int32_t angle_err, float scaler, bool disable_integrator);
26 
27  void reset_I();
28 
29  void autotune_start(void) { autotune.start(); }
30  void autotune_restore(void) { autotune.stop(); }
31 
32  const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; }
33 
34  static const struct AP_Param::GroupInfo var_info[];
35 
36 
37  // tuning accessors
38  void kP(float v) { gains.P.set(v); }
39  void kI(float v) { gains.I.set(v); }
40  void kD(float v) { gains.D.set(v); }
41  void kFF(float v) { gains.FF.set(v); }
42 
43  AP_Float &kP(void) { return gains.P; }
44  AP_Float &kI(void) { return gains.I; }
45  AP_Float &kD(void) { return gains.D; }
46  AP_Float &kFF(void) { return gains.FF; }
47 
48 private:
52  uint32_t _last_t;
53  float _last_out;
54 
56 
57  int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator);
58 
60 
61 };
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
int32_t get_rate_out(float desired_rate, float scaler)
AP_Float & kP(void)
AP_AutoTune::ATGains gains
void stop(void)
int32_t get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
AP_Float & kI(void)
int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator)
void autotune_start(void)
const DataFlash_Class::PID_Info & get_pid_info(void) const
AP_RollController & operator=(const AP_RollController &)=delete
float v
Definition: Printf.cpp:15
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash)
AP_Float & kD(void)
Common definitions and utility routines for the ArduPilot libraries.
const AP_Vehicle::FixedWing & aparm
static const struct AP_Param::GroupInfo var_info[]
DataFlash_Class::PID_Info _pid_info
void start(void)
AP_Float & kFF(void)
void autotune_restore(void)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214