Browse Source

AC_AttitudeControl: added accessors for P and D RMS controller values

master
Andrew Tridgell 9 years ago
parent
commit
e070aeebe3
  1. 4
      libraries/AC_AttitudeControl/AC_AttitudeControl.h
  2. 32
      libraries/AC_AttitudeControl/ControlMonitor.cpp

4
libraries/AC_AttitudeControl/AC_AttitudeControl.h

@ -376,6 +376,10 @@ public:
// return current RMS controller filter for each axis // return current RMS controller filter for each axis
float control_monitor_rms_output_roll(void) const; 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_pitch(void) const;
float control_monitor_rms_output_yaw(void) const; float control_monitor_rms_output_yaw(void) const;
}; };

32
libraries/AC_AttitudeControl/ControlMonitor.cpp

@ -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 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 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 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 return current controller RMS filter value for yaw
*/ */

Loading…
Cancel
Save