@ -87,6 +87,13 @@ const AP_Param::GroupInfo AC_WeatherVane::var_info[] = {
@@ -87,6 +87,13 @@ const AP_Param::GroupInfo AC_WeatherVane::var_info[] = {
// @User: Standard
AP_GROUPINFO ( " LAND " , 8 , AC_WeatherVane , _landing_direction , - 1 ) ,
// @Param: OPTIONS
// @DisplayName: Weathervaning options
// @Description: Options impacting weathervaning behaviour
// @Bitmask: 0:Use pitch when nose or tail-in for faster weathervaning
// @User: Standard
AP_GROUPINFO ( " OPTIONS " , 9 , AC_WeatherVane , _options , 0 ) ,
AP_GROUPEND
} ;
@ -97,7 +104,7 @@ AC_WeatherVane::AC_WeatherVane(void)
@@ -97,7 +104,7 @@ AC_WeatherVane::AC_WeatherVane(void)
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
bool AC_WeatherVane : : get_yaw_out ( float & yaw_output , const int16_t pilot_yaw , const float hgt , const float roll_cdeg , const float pitch_cdeg , const bool is_takeoff , const bool is_landing )
bool AC_WeatherVane : : get_yaw_out ( float & yaw_output , const int16_t pilot_yaw , const float hgt , const float roll_cdeg , float pitch_cdeg , const bool is_takeoff , const bool is_landing )
{
Direction dir = ( Direction ) _direction . get ( ) ;
if ( ( dir = = Direction : : OFF ) | | ! allowed | | ( pilot_yaw ! = 0 ) | | ! is_positive ( _gain ) ) {
@ -159,13 +166,17 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con
@@ -159,13 +166,17 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con
const float deadzone_cdeg = _min_dz_ang_deg * 100.0 ;
float output = 0.0 ;
const char * dir_string = " " ;
// should we enable pitch input for nose-in and tail-in?
const bool pitch_enable = ( uint8_t ( _options . get ( ) ) & uint8_t ( Options : : PITCH_ENABLE ) ) ! = 0 ;
switch ( dir ) {
case Direction : : OFF :
reset ( ) ;
return false ;
case Direction : : NOSE_IN :
if ( is_positive ( pitch_cdeg ) ) {
if ( pitch_enable & & is_positive ( pitch_cdeg ) ) {
output = fabsf ( roll_cdeg ) + pitch_cdeg ;
} else {
output = MAX ( fabsf ( roll_cdeg ) - deadzone_cdeg , 0.0 ) ;
@ -193,7 +204,7 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con
@@ -193,7 +204,7 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con
break ;
case Direction : : TAIL_IN :
if ( is_negative ( pitch_cdeg ) ) {
if ( pitch_enable & & is_negative ( pitch_cdeg ) ) {
output = fabsf ( roll_cdeg ) - pitch_cdeg ;
} else {
output = MAX ( fabsf ( roll_cdeg ) - deadzone_cdeg , 0.0 ) ;