mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_AutoTune: fix yaw feedforward test
This commit is contained in:
parent
f0042b3909
commit
b260839b13
@ -59,14 +59,14 @@ const AP_Param::GroupInfo AC_AutoTune_Heli::var_info[] = {
|
||||
// @Description: 1-byte bitmap of axes to autotune
|
||||
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("AXES", 1, AC_AutoTune_Heli, axis_bitmask, 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
|
||||
AP_GROUPINFO("AXES", 1, AC_AutoTune_Heli, axis_bitmask, 1), // AUTOTUNE_AXIS_BITMASK_DEFAULT
|
||||
|
||||
// @Param: SEQ
|
||||
// @DisplayName: AutoTune Sequence Bitmask
|
||||
// @Description: 2-byte bitmask to select what tuning should be performed. Max gain automatically performed if Rate D is selected. Values: 7:All,1:VFF Only,2:Rate D Only,4:Angle P Only,8:Max Gain Only,3:VFF and Rate D (incl max gain),5:VFF and Angle P,13:VFF max gain and angle P
|
||||
// @Bitmask: 0:VFF,1:Rate D,2:Angle P,3:Max Gain Only
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SEQ", 2, AC_AutoTune_Heli, seq_bitmask, 5),
|
||||
AP_GROUPINFO("SEQ", 2, AC_AutoTune_Heli, seq_bitmask, 3),
|
||||
|
||||
// @Param: FRQ_MIN
|
||||
// @DisplayName: AutoTune minimum sweep frequency
|
||||
@ -863,7 +863,7 @@ void AC_AutoTune_Heli::rate_ff_test_run(float max_angle_cd, float target_rate_cd
|
||||
attitude_control->input_euler_angle_roll_pitch_yaw(start_angles.x, start_angles.y, angle_request_cd.get(), false);
|
||||
} else if (ff_test_phase == 2 ) {
|
||||
angle_request_cd.apply(0.0f, AP::scheduler().get_loop_period_s());
|
||||
attitude_control->input_euler_angle_roll_pitch_yaw(start_angles.x, start_angles.y, angle_request_cd.get(), false);
|
||||
attitude_control->input_euler_angle_roll_pitch_yaw(start_angles.x, start_angles.y, wrap_360_cd(trim_heading + angle_request_cd.get()), false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user