mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_PID: updates for new AP_Param API
This commit is contained in:
parent
5a9ba4aeb4
commit
9349259487
@ -32,6 +32,8 @@ public:
|
|||||||
const float & initial_d = 0.0,
|
const float & initial_d = 0.0,
|
||||||
const int16_t & initial_imax = 0.0)
|
const int16_t & initial_imax = 0.0)
|
||||||
{
|
{
|
||||||
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
|
||||||
_kp = initial_p;
|
_kp = initial_p;
|
||||||
_ki = initial_i;
|
_ki = initial_i;
|
||||||
_kd = initial_d;
|
_kd = initial_d;
|
||||||
|
Loading…
Reference in New Issue
Block a user