APM:Libraries
Public Member Functions | List of all members
AC_P Class Reference

Object managing one P controller. More...

#include <AC_P.h>

Collaboration diagram for AC_P:
[legend]

Public Member Functions

 AC_P (const float &initial_p=0.0f)
 
float get_p (float error) const
 
void load_gains ()
 
void save_gains ()
 

parameter accessors

static const struct AP_Param::GroupInfo var_info []
 
AP_Float _kp
 
void operator() (const float p)
 Overload the function call operator to permit relatively easy initialisation. More...
 
AP_Float & kP ()
 
const AP_Float & kP () const
 
void kP (const float v)
 

Detailed Description

Object managing one P controller.

Definition at line 13 of file AC_P.h.

Constructor & Destructor Documentation

◆ AC_P()

AC_P::AC_P ( const float &  initial_p = 0.0f)
inline

Constructor for P that saves its settings to EEPROM

Note
PIs must be named to avoid either multiple parameters with the same name, or an overly complex constructor.
Parameters
initial_pInitial value for the P term.

Definition at line 23 of file AC_P.h.

Here is the call graph for this function:

Member Function Documentation

◆ get_p()

float AC_P::get_p ( float  error) const

Iterate the P controller, return the new control value

Positive error produces positive output.

Parameters
errorThe measured error value
dtThe time delta in milliseconds (note that update interval cannot be more than 65.535 seconds due to limited range of the data type).
Returns
The updated control output.

Definition at line 15 of file AC_P.cpp.

Referenced by AC_P(), AR_AttitudeControl::get_steering_out_heading(), AC_AttitudeControl::input_shaping_rate_predictor(), and AC_PosControl::run_z_controller().

Here is the caller graph for this function:

◆ kP() [1/3]

AP_Float& AC_P::kP ( )
inline

◆ kP() [2/3]

const AP_Float& AC_P::kP ( ) const
inline

Definition at line 59 of file AC_P.h.

◆ kP() [3/3]

void AC_P::kP ( const float  v)
inline

Definition at line 60 of file AC_P.h.

◆ load_gains()

void AC_P::load_gains ( )

Load gain properties

Definition at line 20 of file AC_P.cpp.

Referenced by AC_P().

Here is the caller graph for this function:

◆ operator()()

void AC_P::operator() ( const float  p)
inline

Overload the function call operator to permit relatively easy initialisation.

Definition at line 55 of file AC_P.h.

◆ save_gains()

void AC_P::save_gains ( )

Save gain properties

Definition at line 25 of file AC_P.cpp.

Referenced by AC_P().

Here is the caller graph for this function:

Member Data Documentation

◆ _kp

AP_Float AC_P::_kp
private

Definition at line 65 of file AC_P.h.

Referenced by AC_P(), get_p(), kP(), load_gains(), operator()(), and save_gains().

◆ var_info

const AP_Param::GroupInfo AC_P::var_info
static
Initial value:
= {
AP_GROUPINFO("P", 0, AC_P, _kp, 0),
}

Definition at line 62 of file AC_P.h.

Referenced by AC_P().


The documentation for this class was generated from the following files: