mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AC_AttitudeControl: added accessors for P and D RMS controller values
This commit is contained in:
parent
1c463e3f3b
commit
e070aeebe3
@ -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;
|
||||
};
|
||||
|
@ -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
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user