123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_Param/AP_Param.h>
- #include <stdlib.h>
- #include <cmath>
- class AC_P {
- public:
-
-
-
-
-
-
-
- AC_P(const float &initial_p = 0.0f)
- {
- AP_Param::setup_object_defaults(this, var_info);
- _kp = initial_p;
- }
-
-
-
-
-
-
-
-
-
-
-
-
- float get_p(float error) const;
-
-
- void load_gains();
-
-
- void save_gains();
-
-
-
- void operator() (const float p) { _kp = p; }
-
- AP_Float &kP() { return _kp; }
- const AP_Float &kP() const { return _kp; }
- void kP(const float v) { _kp.set(v); }
- static const struct AP_Param::GroupInfo var_info[];
- private:
- AP_Float _kp;
- };
|