AC_AttitudeControl: added get_rpy_srate()

This commit is contained in:
Andrew Tridgell 2022-04-26 19:07:20 +10:00 committed by Randy Mackay
parent 3c6e4d907c
commit 9f49570f7f
2 changed files with 23 additions and 0 deletions

View File

@ -11,6 +11,8 @@ extern const AP_HAL::HAL& hal;
# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium
#endif
AC_AttitudeControl *AC_AttitudeControl::_singleton;
// table of user settable parameters
const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
@ -1129,3 +1131,14 @@ bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix,
}
return true;
}
/*
get the slew rate for roll, pitch and yaw, for oscillation
detection in lua scripts
*/
void AC_AttitudeControl::get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate)
{
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;
}

View File

@ -64,9 +64,14 @@ public:
_aparm(aparm),
_motors(motors)
{
_singleton = this;
AP_Param::setup_object_defaults(this, var_info);
}
static AC_AttitudeControl *get_singleton(void) {
return _singleton;
}
// Empty destructor to suppress compiler warning
virtual ~AC_AttitudeControl() {}
@ -363,6 +368,9 @@ public:
// enable inverted flight on backends that support it
virtual void set_inverted_flight(bool inverted) {}
// 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[];
@ -483,6 +491,8 @@ protected:
const AP_Vehicle::MultiCopter &_aparm;
AP_Motors& _motors;
static AC_AttitudeControl *_singleton;
protected:
/*
state of control monitoring