APM:Libraries
AP_YawController.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 <DataFlash/DataFlash.h>
7 #include <cmath>
8 
10 public:
12  : aparm(parms)
13  , _ahrs(ahrs)
14  {
16  _pid_info.desired = 0;
17  _pid_info.FF = 0;
18  _pid_info.P = 0;
19  }
20 
21  /* Do not allow copies */
22  AP_YawController(const AP_YawController &other) = delete;
24 
25  int32_t get_servo_out(float scaler, bool disable_integrator);
26 
27  void reset_I();
28 
29  const DataFlash_Class::PID_Info& get_pid_info(void) const {return _pid_info; }
30 
31  static const struct AP_Param::GroupInfo var_info[];
32 
33 private:
35  AP_Float _K_A;
36  AP_Float _K_I;
37  AP_Float _K_D;
38  AP_Float _K_FF;
39  AP_Int16 _imax;
40  uint32_t _last_t;
41  float _last_out;
44  float _K_D_last;
45 
46  float _integrator;
47 
49 
51 };
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
DataFlash_Class::PID_Info _pid_info
static const struct AP_Param::GroupInfo var_info[]
int32_t get_servo_out(float scaler, bool disable_integrator)
const AP_Vehicle::FixedWing & aparm
const DataFlash_Class::PID_Info & get_pid_info(void) const
AP_YawController & operator=(const AP_YawController &)=delete
Common definitions and utility routines for the ArduPilot libraries.
AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214