Plane: added TKOFF_HEAD_HOLD option

this allows control over whether ArduPlane tries to hold heading
during auto takeoff. For hand launches it can be better to hold the
wings level and not attempt to hold heading during takeoff to prevent
the possibility of a stall during the climb out.

Thanks to Chris Miser from Falcon UAV for the feedback that led to
this option.
This commit is contained in:
Andrew Tridgell 2013-03-27 10:27:14 +11:00
parent 92ddd4b5d1
commit f077f54e6a
3 changed files with 10 additions and 1 deletions

View File

@ -1030,7 +1030,7 @@ static void update_current_flight_mode(void)
switch(nav_command_ID) {
case MAV_CMD_NAV_TAKEOFF:
if (hold_course != -1 && g.rudder_steer == 0) {
if (hold_course != -1 && g.rudder_steer == 0 && g.takeoff_heading_hold != 0) {
calc_nav_roll();
} else {
nav_roll_cd = 0;

View File

@ -80,6 +80,7 @@ public:
k_param_ins, // libraries/AP_InertialSensor variables
k_param_takeoff_throttle_min_speed,
k_param_takeoff_throttle_min_accel,
k_param_takeoff_heading_hold,
// 110: Telemetry control
//
@ -358,6 +359,7 @@ public:
AP_Int8 rudder_steer;
AP_Float takeoff_throttle_min_speed;
AP_Float takeoff_throttle_min_accel;
AP_Int8 takeoff_heading_hold;
// RC channels
RC_Channel channel_roll;

View File

@ -106,6 +106,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: User
GSCALAR(takeoff_throttle_min_accel, "TKOFF_THR_MINACC", 0),
// @Param: TKOFF_HEAD_HOLD
// @DisplayName: Auto takeoff heading hold
// @Description: This controls whether APM tries to hold a constant heading during automatic takeoff. The default is 1, which means that it remembers the heading when auto takeoff is triggered, and tries to hold that heading until the target altitude is reached. This is the correct setting for wheeled takeoff. For a hand launch, it may be better to set this to 0, which will tell APM to hold the wings level, but not attempt to hold a particular heading. That can prevent the aircraft from rolling too much on takeoff, which can cause a stall.
// @Values: 0:NoHeadingHold,1:HeadingHold
// @User: User
GSCALAR(takeoff_heading_hold, "TKOFF_HEAD_HOLD", 1),
// @Param: RUDDER_STEER
// @DisplayName: Rudder steering on takeoff and landing
// @Description: When enabled, only rudder will be used for steering during takeoff and landing, with the ailerons used to hold the plane level