AC_AttitudeControl: added accessors for P and D RMS controller values

This commit is contained in:
Andrew Tridgell 2016-06-09 16:25:19 +10:00
parent 1c463e3f3b
commit e070aeebe3
2 changed files with 36 additions and 0 deletions

View File

@ -376,6 +376,10 @@ public:
// return current RMS controller filter for each axis
float control_monitor_rms_output_roll(void) const;
float control_monitor_rms_output_roll_P(void) const;
float control_monitor_rms_output_roll_D(void) const;
float control_monitor_rms_output_pitch_P(void) const;
float control_monitor_rms_output_pitch_D(void) const;
float control_monitor_rms_output_pitch(void) const;
float control_monitor_rms_output_yaw(void) const;
};

View File

@ -61,6 +61,22 @@ float AC_AttitudeControl::control_monitor_rms_output_roll(void) const
return sqrtf(_control_monitor.rms_roll_P + _control_monitor.rms_roll_D);
}
/*
return current controller RMS filter value for roll_P
*/
float AC_AttitudeControl::control_monitor_rms_output_roll_P(void) const
{
return sqrtf(_control_monitor.rms_roll_P);
}
/*
return current controller RMS filter value for roll_D
*/
float AC_AttitudeControl::control_monitor_rms_output_roll_D(void) const
{
return sqrtf(_control_monitor.rms_roll_D);
}
/*
return current controller RMS filter value for pitch
*/
@ -69,6 +85,22 @@ float AC_AttitudeControl::control_monitor_rms_output_pitch(void) const
return sqrtf(_control_monitor.rms_pitch_P + _control_monitor.rms_pitch_D);
}
/*
return current controller RMS filter value for pitch_P
*/
float AC_AttitudeControl::control_monitor_rms_output_pitch_P(void) const
{
return sqrtf(_control_monitor.rms_pitch_P);
}
/*
return current controller RMS filter value for pitch_D
*/
float AC_AttitudeControl::control_monitor_rms_output_pitch_D(void) const
{
return sqrtf(_control_monitor.rms_pitch_D);
}
/*
return current controller RMS filter value for yaw
*/