APM:Libraries
|
Object managing one P controller. More...
#include <AC_P.h>
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) |
|
inline |
float AC_P::get_p | ( | float | error | ) | const |
Iterate the P controller, return the new control value
Positive error produces positive output.
error | The measured error value |
dt | The time delta in milliseconds (note that update interval cannot be more than 65.535 seconds due to limited range of the data type). |
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().
|
inline |
Definition at line 58 of file AC_P.h.
Referenced by AC_AttitudeControl_Sub::AC_AttitudeControl_Sub(), AC_WPNav::advance_wp_target_along_track(), AC_Loiter::calc_desired_velocity(), AC_PosControl::calc_leash_length_xy(), AC_PosControl::calc_leash_length_z(), AC_PosControl::get_stopping_point_xy(), AC_PosControl::get_stopping_point_z(), AC_AttitudeControl::max_angle_step_bf_pitch(), AC_AttitudeControl::max_angle_step_bf_roll(), AC_AttitudeControl::max_angle_step_bf_yaw(), AC_PosControl::run_xy_controller(), AC_PosControl::run_z_controller(), AC_AttitudeControl::thrust_heading_rotation_angles(), and AC_AttitudeControl::update_ang_vel_target_from_att_error().
void AC_P::load_gains | ( | ) |
|
inline |
void AC_P::save_gains | ( | ) |
|
private |
Definition at line 65 of file AC_P.h.
Referenced by AC_P(), get_p(), kP(), load_gains(), operator()(), and save_gains().
|
static |