Skip to content

Takeoff Mode (Fixed-Wing)

The Takeoff flight mode causes the vehicle to take off to a specified height and then enter Hold mode.

Vehicles are hand or catapult launched by default, but can also be configured to use a runway takeoff when supported by the hardware.

INFO

  • Mode is automatic - no user intervention is required to control the vehicle.
  • Mode requires at least a valid local position estimate (does not require a global position).
    • Flying vehicles can't switch to this mode without valid local position.
    • Flying vehicles will failsafe if they lose the position estimate.
    • Disarmed vehicles can switch to mode without valid position estimate but can't arm.
  • RC control switches can be used to change flight modes.
  • RC stick movement is ignored in catapult takeoff but can can be used to nudge the vehicle in runway takeoff.
  • The Failure Detector will automatically stop the engines if there is a problem on takeoff.

Technical Summary

Takeoff mode (and fixed wing mission takeoff) has two modalities: catapult/hand-launch or runway takeoff (hardware-dependent). The mode defaults to catapult/hand launch, but can be set to runway takeoff by setting RWTO_TKOFF to 1.

To use Takeoff mode you first switch to the mode, and then arm the vehicle. The acceleration of hand/catapult launch triggers the motors to start. For runway launch, motors ramp up automatically once the vehicle has been armed.

Irrespective of the modality, a flight path (starting point and takeoff course) and clearance altitude are defined:

  • The starting point is the vehicle position when the takeoff mode is first entered.
  • The course is set to the vehicle heading on arming
  • The clearance altitude is set to MIS_TAKEOFF_ALT.

On takeoff, the aircraft will follow line defined by the starting point and course, climbing at the maximum climb rate (FW_T_CLMB_MAX) until reaching the clearance altitude. Reaching the clearance altitude causes the vehicle to enter Hold mode.

Parameters

Parameters that affect both catapult/hand-launch and runway takeoffs:

ParameterDescription
MIS_TAKEOFF_ALTMinimum altitude setpoint above Home that the vehicle will climb to during takeoff.
FW_TKO_AIRSPDTakeoff airspeed (is set to FW_AIRSPD_MIN if not defined by operator)
FW_TKO_PITCH_MINThis is the minimum pitch angle setpoint during the climbout phase
FW_T_CLMB_MAXMaximum climb rate.
FW_FLAPS_TO_SCLFlaps setpoint during takeoff

INFO

The vehicle always respects normal FW max/min throttle settings during takeoff (FW_THR_MIN, FW_THR_MAX).

Catapult/Hand Launch

In catapult/hand-launch mode the vehicle waits to detect launch (based on acceleration trigger). On launch it enables the motor(s) and climbs with the maximum climb rate FW_T_CLMB_MAX while keeping the pitch setpoint above FW_TKO_PITCH_MIN. Once it reaches MIS_TAKEOFF_ALT it will automatically switch to Hold mode and loiter.

All RC stick movement is ignored during the full takeoff sequence.

To launch in this mode:

  1. Arm the vehicle
  2. Put the vehicle into Takeoff mode
  3. Launch/throw the vehicle (firmly) directly into the wind. You can also shake the vehicle first, wait till the motor spins up and then throw it

Parameters (Launch Detector)

The launch detector is affected by the following parameters:

ParameterDescription
FW_LAUN_DETCN_ONEnable automatic launch detection. If disabled motors spin up on arming already
FW_LAUN_AC_THLDAcceleration threshold (acceleration in body-forward direction must be above this value)
FW_LAUN_AC_TTrigger time (acceleration must be above threshold for this amount of seconds)
FW_LAUN_MOT_DELDelay from launch detection to motor spin up

Runway Takeoff

Runway takeoffs can be used by vehicles with landing gear and and steerable wheel (only). You will first need to enable the wheel controller using the parameter FW_W_EN.

Vehicle should be centered and aligned with runway when takeoff is initiated. The operator can "nudge" the vehicle while on the runway to help keeping it centered and aligned (see RWTO_NUDGE).

The runway takeoff mode has the following phases:

  1. Throttle ramp: Throttle is ramped up within RWTO_RAMP_TIME to RWTO_MAX_THR.
  2. Clamped to runway: Pitch fixed, no roll and takeoff path controlled until the rotation airspeed (RWTO_ROT_AIRSPD) is reached. The operator is able to nudge the vehicle left/right via yaw stick.
  3. Climbout: Increase pitch setpoint and climb to takeoff altitude. To prevent wingstrikes, the controller will keep the roll setpoint locked to 0 when close to the ground, and then gradually allow more roll while climbing. It is based on the vehicle geometry as configured in FW_WING_SPAN and FW_WING_HEIGHT.

INFO

For a smooth takeoff, the runway wheel controller possibly needs to be tuned. It consists of a rate controller (P-I-FF-controller with the parameters FW_WR_P, FW_WR_I, FW_WR_FF) and an outer loop that calculates heading setpoints from course errors and can be tuned via RWTO_NPFG_PERIOD.

Parameters (Runway Takeoff)

Runway takeoff is affected by the following parameters:

ParameterDescription
RWTO_TKOFFEnable runway takeoff
FW_W_ENEnable wheel controller
RWTO_MAX_THRMax throttle during runway takeoff
RWTO_RAMP_TIMEThrottle ramp up time
RWTO_ROT_AIRSPDAirspeed threshold to start rotation (pitching up). If not configured by operator is set to 0.9*FW_TKO_AIRSPD.
RWTO_ROT_TIMEThis is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation.
FW_TKO_AIRSPDAirspeed setpoint during the takeoff climbout phase (after rotation). If not configured by operator is set to FW_AIRSPD_MIN.
RWTO_NUDGEEnable wheel controller nudging while on the runway
FW_WING_SPANThe wingspan of the vehicle. Used to prevent wingstrikes.
FW_WING_HEIGHTThe height of the wings above ground (ground clearance). Used to prevent wingstrikes.
RWTO_NPFG_PERIODL1 period while steering on runway. Increase for less aggressive response to course errors.

See Also