diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 595c3943f1..1e24000057 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -1133,12 +1133,12 @@ bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix, } /* - get the PDmod value for roll, pitch and yaw, for oscillation - detection in lua scripts + get the slew rate for roll, pitch and yaw, for oscillation + detection in lua scripts */ -void AC_AttitudeControl::get_rpy_PDmod(float &roll_dmod, float &pitch_dmod, float &yaw_dmod) +void AC_AttitudeControl::get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate) { - roll_dmod = get_rate_roll_pid().get_pid_info().Dmod; - pitch_dmod = get_rate_pitch_pid().get_pid_info().Dmod; - yaw_dmod = get_rate_yaw_pid().get_pid_info().Dmod; + roll_srate = get_rate_roll_pid().get_pid_info().slew_rate; + pitch_srate = get_rate_pitch_pid().get_pid_info().slew_rate; + yaw_srate = get_rate_yaw_pid().get_pid_info().slew_rate; } diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index bc4439ed94..c9fba10612 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -368,9 +368,9 @@ public: // enable inverted flight on backends that support it virtual void set_inverted_flight(bool inverted) {} - // get the PDmod value for roll, pitch and yaw, for oscillation detection in lua scripts - void get_rpy_PDmod(float &roll_dmod, float &pitch_dmod, float &yaw_dmod); - + // get the slew rate value for roll, pitch and yaw, for oscillation detection in lua scripts + void get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate); + // User settable parameters static const struct AP_Param::GroupInfo var_info[];