AC_AttitudeControl: WeatherVane: add tail in option

This commit is contained in:
Peter Hall 2022-01-23 22:22:41 +00:00 committed by Andrew Tridgell
parent a79359dc67
commit 8fdc85ccbe
2 changed files with 12 additions and 0 deletions

View File

@ -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) {

View File

@ -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