AC_PID: added set_desired_rate() interface
used to setup _pid_info for logging
This commit is contained in:
parent
6000bb0c32
commit
3ec8857fbc
@ -56,7 +56,6 @@ AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, floa
|
||||
float AC_HELI_PID::get_vff(float requested_rate)
|
||||
{
|
||||
_pid_info.FF = (float)requested_rate * _vff;
|
||||
_pid_info.desired = requested_rate;
|
||||
return _pid_info.FF;
|
||||
}
|
||||
|
||||
@ -73,7 +72,6 @@ float AC_HELI_PID::get_aff(float requested_rate)
|
||||
|
||||
_pid_info.AFF = derivative * _aff;
|
||||
_last_requested_rate = requested_rate;
|
||||
_pid_info.desired = requested_rate;
|
||||
return _pid_info.AFF;
|
||||
}
|
||||
|
||||
|
@ -76,6 +76,9 @@ public:
|
||||
float get_integrator() const { return _integrator; }
|
||||
void set_integrator(float i) { _integrator = i; }
|
||||
|
||||
// set the designed rate (for logging purposes)
|
||||
void set_desired_rate(float desired) { _pid_info.desired = desired; }
|
||||
|
||||
const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; }
|
||||
|
||||
// parameter var table
|
||||
|
Loading…
Reference in New Issue
Block a user