AC_AttControl: remove comment, fix formatting
This commit is contained in:
parent
3c4d226b64
commit
02eda4dcab
@ -9,7 +9,6 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
|
||||
|
||||
// 0, 1 were RATE_RP_MAX, RATE_Y_MAX
|
||||
|
||||
// BUG: SLEW_YAW's behavior does not match its parameter documentation
|
||||
// @Param: SLEW_YAW
|
||||
// @DisplayName: Yaw target slew rate
|
||||
// @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
|
||||
@ -258,7 +257,6 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle
|
||||
att_error_euler_rad.z = wrap_PI(_att_target_euler_rad.z - _ahrs.yaw);
|
||||
|
||||
// Constrain the yaw angle error
|
||||
// BUG: SLEW_YAW's behavior does not match its parameter documentation
|
||||
if (slew_yaw) {
|
||||
att_error_euler_rad.z = constrain_float(att_error_euler_rad.z,-get_slew_yaw_rads(),get_slew_yaw_rads());
|
||||
}
|
||||
|
@ -22,7 +22,6 @@
|
||||
#define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS radians(720.0f) // maximum body-frame acceleration limit for the stability controller (for roll and pitch axis)
|
||||
#define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS radians(90.0f) // minimum body-frame acceleration limit for the stability controller (for yaw axis)
|
||||
#define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS radians(360.0f) // maximum body-frame acceleration limit for the stability controller (for yaw axis)
|
||||
// BUG: SLEW_YAW's behavior does not match its parameter documentation
|
||||
#define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS 1000 // constraint on yaw angle error in degrees. This should lead to maximum turn rate of 10deg/sed * Stab Rate P so by default will be 45deg/sec.
|
||||
#define AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS 110000.0f // default maximum acceleration for roll/pitch axis in centidegrees/sec/sec
|
||||
#define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS 27000.0f // default maximum acceleration for yaw axis in centidegrees/sec/sec
|
||||
@ -263,7 +262,6 @@ protected:
|
||||
float get_tilt_limit_rad() { return radians(_aparm.angle_max*0.01f); }
|
||||
|
||||
// Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
|
||||
// BUG: SLEW_YAW's behavior does not match its parameter documentation
|
||||
AP_Float _slew_yaw;
|
||||
|
||||
// Maximum rotation acceleration for earth-frame roll axis
|
||||
@ -311,7 +309,7 @@ protected:
|
||||
int16_t _angle_boost;
|
||||
|
||||
// Specifies whether the attitude controller should use the acceleration limit
|
||||
bool _att_ctrl_use_accel_limit;
|
||||
bool _att_ctrl_use_accel_limit;
|
||||
|
||||
// Filtered throttle input - used to limit lean angle when throttle is saturated
|
||||
LowPassFilterFloat _throttle_in_filt;
|
||||
|
Loading…
Reference in New Issue
Block a user