From 8fdc85ccbead3f276a94162658f480d45bf330aa Mon Sep 17 00:00:00 2001 From: Peter Hall Date: Sun, 23 Jan 2022 22:22:41 +0000 Subject: [PATCH] AC_AttitudeControl: WeatherVane: add tail in option --- libraries/AC_AttitudeControl/AC_WeatherVane.cpp | 11 +++++++++++ libraries/AC_AttitudeControl/AC_WeatherVane.h | 1 + 2 files changed, 12 insertions(+) diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp index e0f5601747..e74a8565ea 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp @@ -163,6 +163,17 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con dir_string = "side in"; break; + case Direction::TAIL_IN: + if (is_negative(pitch_cdeg)) { + output = fabsf(roll_cdeg) - pitch_cdeg; + } else { + output = MAX(fabsf(roll_cdeg) - deadzone_cdeg, 0.0); + } + if (is_positive(roll_cdeg)) { + output *= -1.0; + } + dir_string = "tail in"; + break; } if (!active_msg_sent) { diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.h b/libraries/AC_AttitudeControl/AC_WeatherVane.h index 397da41d88..a6cf35139b 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.h +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.h @@ -28,6 +28,7 @@ class AC_WeatherVane { NOSE_IN = 1, // Only nose into wind NOSE_OR_TAIL_IN = 2, // Nose in or tail into wind, which ever is closest SIDE_IN = 3, // Side into wind for copter tailsitters + TAIL_IN = 4, // backwards, for tailsitters, makes it easier to descend }; // Paramaters