AC_AttitudeControl: re-order initialiser lines so -Werror=reorder will work

This commit is contained in:
Peter Barker 2024-09-20 22:20:41 +10:00 committed by Peter Barker
parent a75b8a9269
commit b480416c3d
2 changed files with 7 additions and 7 deletions

View File

@ -40,9 +40,9 @@ const AP_Param::GroupInfo AC_CommandModel::var_info[] = {
// Constructor // Constructor
AC_CommandModel::AC_CommandModel(float initial_rate, float initial_expo, float initial_tc) : AC_CommandModel::AC_CommandModel(float initial_rate, float initial_expo, float initial_tc) :
default_rate_tc(initial_tc),
default_rate(initial_rate), default_rate(initial_rate),
default_expo(initial_expo), default_expo(initial_expo)
default_rate_tc(initial_tc)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
} }

View File

@ -331,16 +331,16 @@ AC_PosControl::AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav,
_inav(inav), _inav(inav),
_motors(motors), _motors(motors),
_attitude_control(attitude_control), _attitude_control(attitude_control),
_p_pos_xy(POSCONTROL_POS_XY_P),
_p_pos_z(POSCONTROL_POS_Z_P), _p_pos_z(POSCONTROL_POS_Z_P),
_pid_vel_xy(POSCONTROL_VEL_XY_P, POSCONTROL_VEL_XY_I, POSCONTROL_VEL_XY_D, 0.0f, POSCONTROL_VEL_XY_IMAX, POSCONTROL_VEL_XY_FILT_HZ, POSCONTROL_VEL_XY_FILT_D_HZ),
_pid_vel_z(POSCONTROL_VEL_Z_P, 0.0f, 0.0f, 0.0f, POSCONTROL_VEL_Z_IMAX, POSCONTROL_VEL_Z_FILT_HZ, POSCONTROL_VEL_Z_FILT_D_HZ), _pid_vel_z(POSCONTROL_VEL_Z_P, 0.0f, 0.0f, 0.0f, POSCONTROL_VEL_Z_IMAX, POSCONTROL_VEL_Z_FILT_HZ, POSCONTROL_VEL_Z_FILT_D_HZ),
_pid_accel_z(POSCONTROL_ACC_Z_P, POSCONTROL_ACC_Z_I, POSCONTROL_ACC_Z_D, 0.0f, POSCONTROL_ACC_Z_IMAX, 0.0f, POSCONTROL_ACC_Z_FILT_HZ, 0.0f), _pid_accel_z(POSCONTROL_ACC_Z_P, POSCONTROL_ACC_Z_I, POSCONTROL_ACC_Z_D, 0.0f, POSCONTROL_ACC_Z_IMAX, 0.0f, POSCONTROL_ACC_Z_FILT_HZ, 0.0f),
_p_pos_xy(POSCONTROL_POS_XY_P),
_pid_vel_xy(POSCONTROL_VEL_XY_P, POSCONTROL_VEL_XY_I, POSCONTROL_VEL_XY_D, 0.0f, POSCONTROL_VEL_XY_IMAX, POSCONTROL_VEL_XY_FILT_HZ, POSCONTROL_VEL_XY_FILT_D_HZ),
_vel_max_down_cms(POSCONTROL_SPEED_DOWN),
_vel_max_up_cms(POSCONTROL_SPEED_UP),
_vel_max_xy_cms(POSCONTROL_SPEED), _vel_max_xy_cms(POSCONTROL_SPEED),
_accel_max_z_cmss(POSCONTROL_ACCEL_Z), _vel_max_up_cms(POSCONTROL_SPEED_UP),
_vel_max_down_cms(POSCONTROL_SPEED_DOWN),
_accel_max_xy_cmss(POSCONTROL_ACCEL_XY), _accel_max_xy_cmss(POSCONTROL_ACCEL_XY),
_accel_max_z_cmss(POSCONTROL_ACCEL_Z),
_jerk_max_xy_cmsss(POSCONTROL_JERK_XY * 100.0), _jerk_max_xy_cmsss(POSCONTROL_JERK_XY * 100.0),
_jerk_max_z_cmsss(POSCONTROL_JERK_Z * 100.0) _jerk_max_z_cmsss(POSCONTROL_JERK_Z * 100.0)
{ {