23 AC_P(
const float &initial_p = 0.0
f)
59 const AP_Float &
kP()
const {
return _kp; }
60 void kP(
const float v) {
_kp.set(v); }
static const struct AP_Param::GroupInfo var_info[]
Object managing one P controller.
A system for managing and storing variables that are of general interest to the system.
const AP_Float & kP() const
AC_P(const float &initial_p=0.0f)
Common definitions and utility routines for the ArduPilot libraries.
void operator()(const float p)
Overload the function call operator to permit relatively easy initialisation.
#define error(fmt, args ...)
float get_p(float error) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)