APM:Libraries
AC_HELI_PID.h
Go to the documentation of this file.
1 #pragma once
2 
5 
6 #include <AP_Common/AP_Common.h>
7 #include <AP_Param/AP_Param.h>
8 #include <stdlib.h>
9 #include <cmath>
10 #include "AC_PID.h"
11 
12 #define AC_PID_LEAK_MIN 0.1 // Default I-term Leak Minimum
13 
16 class AC_HELI_PID : public AC_PID {
17 public:
18 
20  AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff);
21 
23  float get_leaky_i(float leak_rate);
24 
25  static const struct AP_Param::GroupInfo var_info[];
26 
27 private:
28  AP_Float _leak_min;
29 
30  float _last_requested_rate; // Requested rate from last iteration, used to calculate rate change of requested rate
31 };
float _last_requested_rate
Definition: AC_HELI_PID.h:30
Generic PID algorithm, with EEPROM-backed storage of constants.
float get_leaky_i(float leak_rate)
get_leaky_i - replacement for get_i but output is leaded at leak_rate
Definition: AC_HELI_PID.cpp:60
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_HELI_PID.h:25
AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff)
Constructor for PID.
Definition: AC_HELI_PID.cpp:51
A system for managing and storing variables that are of general interest to the system.
Heli PID control class.
Definition: AC_HELI_PID.h:16
AP_Float _leak_min
Definition: AC_HELI_PID.h:28
Common definitions and utility routines for the ArduPilot libraries.
Copter PID control class.
Definition: AC_PID.h:17