APM:Libraries
AC_P.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 
13 class AC_P {
14 public:
15 
23  AC_P(const float &initial_p = 0.0f)
24  {
26  _kp = initial_p;
27  }
28 
41  float get_p(float error) const;
42 
45  void load_gains();
46 
49  void save_gains();
50 
52 
53 
55  void operator() (const float p) { _kp = p; }
56 
57  // accessors
58  AP_Float &kP() { return _kp; }
59  const AP_Float &kP() const { return _kp; }
60  void kP(const float v) { _kp.set(v); }
61 
62  static const struct AP_Param::GroupInfo var_info[];
63 
64 private:
65  AP_Float _kp;
66 };
void save_gains()
Definition: AC_P.cpp:25
void load_gains()
Definition: AC_P.cpp:20
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_P.h:62
Object managing one P controller.
Definition: AC_P.h:13
A system for managing and storing variables that are of general interest to the system.
const AP_Float & kP() const
Definition: AC_P.h:59
#define f(i)
AP_Float _kp
Definition: AC_P.h:65
AC_P(const float &initial_p=0.0f)
Definition: AC_P.h:23
float v
Definition: Printf.cpp:15
void kP(const float v)
Definition: AC_P.h:60
Common definitions and utility routines for the ArduPilot libraries.
void operator()(const float p)
Overload the function call operator to permit relatively easy initialisation.
Definition: AC_P.h:55
#define error(fmt, args ...)
float get_p(float error) const
Definition: AC_P.cpp:15
AP_Float & kP()
Definition: AC_P.h:58
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214