Plane: added support for rate yaw control

to enable for ACRO mode, set ACRO_YAW_RATE to desired maximum rate in
degrees/second, and set YAW_RATE_ENABLE=1 to enable PID tuning of yaw
rate controller

pair programmed with Andy Palmer and Matthew Hampsey
This commit is contained in:
Andrew Tridgell 2021-11-25 18:02:31 +11:00 committed by Peter Barker
parent 6685ce0527
commit b619ee4970
3 changed files with 19 additions and 3 deletions

View File

@ -444,7 +444,12 @@ void Plane::stabilize_acro(float speed_scaler)
steering_control.steering = rudder_input();
if (plane.g2.flight_options & FlightOptions::ACRO_YAW_DAMPER) {
if (g.acro_yaw_rate > 0 && yawController.rate_control_enabled()) {
// user has asked for yaw rate control with yaw rate scaled by ACRO_YAW_RATE
const float rudd_expo = rudder_in_expo(true);
const float yaw_rate = (rudd_expo/SERVO_MAX) * g.acro_yaw_rate;
steering_control.steering = steering_control.rudder = yawController.get_rate_out(yaw_rate, speed_scaler, false);
} else if (plane.g2.flight_options & FlightOptions::ACRO_YAW_DAMPER) {
// use yaw controller
calc_nav_yaw_coordinated(speed_scaler);
} else {

View File

@ -544,6 +544,15 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Standard
GSCALAR(acro_pitch_rate, "ACRO_PITCH_RATE", 180),
// @Param: ACRO_YAW_RATE
// @DisplayName: ACRO mode yaw rate
// @Description: The maximum yaw rate at full stick deflection in ACRO mode. If this is zero then rudder is directly controlled by rudder stick input
// @Units: deg/s
// @Range: 0 500
// @Increment: 1
// @User: Standard
GSCALAR(acro_yaw_rate, "ACRO_YAW_RATE", 0),
// @Param: ACRO_LOCKING
// @DisplayName: ACRO mode attitude locking
// @Description: Enable attitude locking when sticks are released
@ -811,9 +820,9 @@ const AP_Param::Info Plane::var_info[] = {
// @Path: ../libraries/APM_Control/AP_PitchController.cpp
GOBJECT(pitchController, "PTCH", AP_PitchController),
// @Group: YAW2SRV_
// @Group: YAW
// @Path: ../libraries/APM_Control/AP_YawController.cpp
GOBJECT(yawController, "YAW2SRV_", AP_YawController),
GOBJECT(yawController, "YAW", AP_YawController),
// @Group: STEER2SRV_
// @Path: ../libraries/APM_Control/AP_SteerController.cpp

View File

@ -351,6 +351,7 @@ public:
k_param_gcs5, // stream rates
k_param_gcs6, // stream rates
k_param_fence, // vehicle fence
k_param_acro_yaw_rate,
};
AP_Int16 format_version;
@ -420,6 +421,7 @@ public:
AP_Int16 alt_offset;
AP_Int16 acro_roll_rate;
AP_Int16 acro_pitch_rate;
AP_Int16 acro_yaw_rate;
AP_Int8 acro_locking;
// Misc