mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: added FLIGHT_OPTIONS bit to enable yaw control in ACRO mode
this allows for yaw damper in ACRO, which is important on some vehicles with no vertical stabilize See https://discuss.ardupilot.org/t/rudderless-split-rudder-flying-wing/69273/4
This commit is contained in:
parent
4cc92c6b3e
commit
e5308db8c2
@ -363,10 +363,17 @@ void Plane::stabilize_acro(float speed_scaler)
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, pitchController.get_rate_out(pitch_rate, speed_scaler));
|
||||
}
|
||||
|
||||
/*
|
||||
manual rudder for now
|
||||
*/
|
||||
steering_control.steering = steering_control.rudder = rudder_input();
|
||||
steering_control.steering = rudder_input();
|
||||
|
||||
if (plane.g2.flight_options & FlightOptions::ACRO_YAW_DAMPER) {
|
||||
// use yaw controller
|
||||
calc_nav_yaw_coordinated(speed_scaler);
|
||||
} else {
|
||||
/*
|
||||
manual rudder
|
||||
*/
|
||||
steering_control.rudder = steering_control.steering;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -1120,7 +1120,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @Param: FLIGHT_OPTIONS
|
||||
// @DisplayName: Flight mode options
|
||||
// @Description: Flight mode specific options
|
||||
// @Bitmask: 0:Rudder mixing in direct flight modes only (Manual / Stabilize / Acro),1:Use centered throttle in Cruise or FBWB to indicate trim airspeed, 2:Disable attitude check for takeoff arming, 3:Force target airspeed to trim airspeed in Cruise or FBWB, 4: Climb to ALT_HOLD_RTL before turning for RTL.
|
||||
// @Bitmask: 0:Rudder mixing in direct flight modes only (Manual / Stabilize / Acro),1:Use centered throttle in Cruise or FBWB to indicate trim airspeed, 2:Disable attitude check for takeoff arming, 3:Force target airspeed to trim airspeed in Cruise or FBWB, 4: Climb to ALT_HOLD_RTL before turning for RTL, 5:Enable yaw damper in acro mode
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
|
||||
|
||||
|
@ -153,6 +153,7 @@ enum FlightOptions {
|
||||
DISABLE_TOFF_ATTITUDE_CHK = (1 << 2),
|
||||
CRUISE_TRIM_AIRSPEED = (1 << 3),
|
||||
CLIMB_BEFORE_TURN = (1 << 4),
|
||||
ACRO_YAW_DAMPER = (1 << 5),
|
||||
};
|
||||
|
||||
enum CrowFlapOptions {
|
||||
|
Loading…
Reference in New Issue
Block a user