mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AC_HELI_PID: Pass default FF param setting in constructor
This commit is contained in:
parent
575a5ad619
commit
bcc3fa0526
@ -23,8 +23,8 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("D", 2, AC_HELI_PID, _kd, 0),
|
||||
|
||||
// @Param: FC
|
||||
// @DisplayName: PID+FF FeedForward Gain
|
||||
// @Description: FF Gain which produces an output value that is proportional to the current error value
|
||||
// @DisplayName: FF FeedForward Gain
|
||||
// @Description: FF Gain which produces an output value that is proportional to the demanded input
|
||||
AP_GROUPINFO("FF", 4, AC_HELI_PID, _ff, 0),
|
||||
|
||||
// @Param: IMAX
|
||||
@ -40,10 +40,10 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] PROGMEM = {
|
||||
};
|
||||
|
||||
/// Constructor for PID
|
||||
AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt) :
|
||||
AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff) :
|
||||
AC_PID(initial_p, initial_i, initial_d, initial_imax, initial_filt_hz, dt)
|
||||
{
|
||||
_ff = 0.0f;
|
||||
_ff = initial_ff;
|
||||
}
|
||||
|
||||
float AC_HELI_PID::get_ff(float requested_rate) const
|
||||
|
@ -18,7 +18,7 @@ class AC_HELI_PID : public AC_PID {
|
||||
public:
|
||||
|
||||
/// Constructor for PID
|
||||
AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt);
|
||||
AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff);
|
||||
|
||||
/// get_ff - return FeedForward Term
|
||||
float get_ff(float requested_rate) const;
|
||||
|
Loading…
Reference in New Issue
Block a user