Browse Source

Plane: default angle_boost to disabled for tailsitters

master
Mark Whitehorn 5 years ago committed by Andrew Tridgell
parent
commit
788e7a840c
  1. 3
      ArduPlane/quadplane.cpp

3
ArduPlane/quadplane.cpp

@ -490,7 +490,8 @@ static const struct AP_Param::defaults_table_struct defaults_table_tailsitter[] @@ -490,7 +490,8 @@ static const struct AP_Param::defaults_table_struct defaults_table_tailsitter[]
{ "KFF_RDDRMIX", 0.02 },
{ "Q_A_RAT_PIT_FF", 0.2 },
{ "Q_A_RAT_YAW_FF", 0.2 },
{ "Q_A_RAT_YAW_I", 0.18 },
{ "Q_A_RAT_YAW_I", 0.18 },
{ "Q_A_ANGLE_BOOST", 0 },
{ "LIM_PITCH_MAX", 3000 },
{ "LIM_PITCH_MIN", -3000 },
{ "MIXING_GAIN", 1.0 },

Loading…
Cancel
Save