How Can We Help?

INAV VTOL

You are here:
< All Topics

INAV VTOL

Thank you for trying the INAV VTOL. Read every line in this tutorial. Your patience can save both time and potential repair costs for the model.

Who Should Use This Tutorial?

This tutorial is designed for individuals who

  • have prior experience with both INAV multi-rotor and INAV fixed-wing configurations/operations.
  • know how to create a custom mixer for their model.
  • know basic physics of vtol operation

Firmware Status

The firmware is in a flyable state, but it hasn’t undergone extensive testing yet. This means there may be potential issues that have not yet been discovered.

Future Changes

Please be aware that both the setup procedure and firmware may change in response to user feedback and testing results.

Your Feedback Matters

We highly value your feedback as it plays a crucial role in the development and refinement of INAV VTOL capabilities. Please share your experiences, suggestions, and any issues you encounter during testing. Your insights are invaluable in making INAV VTOL better for everyone.

VTOL Configuration Steps

The VTOL functionality is achieved by switching/transitioning between two configurations stored in the FC. VTOL specific configurations are Mixer Profiles with associated PID profiles. One profile set is for fixed-wing(FW) mode, One is for multi-copter(MC) mode. Configuration/Settings other than Mixer/PID profiles are shared among two modes

Alt text
  1. Find a DIFF ALL file for your model and start from there if possible
    • Be aware that MIXER PROFILE 2 RC mode setting introduced by diff file can get your stuck in a mixer_profile. remove or change channel to proceed
  2. Setup Profile 1:
    • Configure it as a normal fixed-wing/multi-copter.
  3. Setup Profile 2:
    • Configure it as a normal multi-copter/fixed-wing.
  4. Mode Tab Settings:
    • Set up switching in the mode tab.
  5. (Recommended)Transition Mixing (Multi-Rotor Profile):
    • Configure transition mixing to gain airspeed in the multi-rotor profile.
  6. (Optional)Automated Switching (RTH):
    • Optionally, set up automated switching in case of failsafe.

STEP0: Load parameter preset/templates

Find a working diff file if you can and start from there. If not, select keep current settings and apply following parameter in cli but read description about which one to apply.

set small_angle = 180
set gyro_main_lpf_hz = 80
set dynamic_gyro_notch_min_hz = 50
set dynamic_gyro_notch_mode = 3D
set motor_pwm_protocol = DSHOT300 #Try dshot first and see if it works
set airmode_type = STICK_CENTER_ONCE


set nav_disarm_on_landing = OFF  #band-aid for false landing detection in NAV landing of multi-copter
set nav_rth_allow_landing = FS_ONLY
set nav_wp_max_safe_distance = 500
set nav_fw_control_smoothness = 2
set nav_fw_launch_max_altitude = 5000

set servo_pwm_rate = 160 #If model using servo for stabilization in MC mode and servo can tolerate it 
set servo_lpf_hz = 30 #If model using servo for stabilization in MC mode


## profile 1 as airplane and profile 2 as multi rotor
mixer_profile 1

set platform_type = AIRPLANE
set model_preview_type = 26
set motorstop_on_low = ON
set mixer_pid_profile_linking = ON

mixer_profile 2

set platform_type = TRICOPTER
set model_preview_type = 1
set mixer_pid_profile_linking = ON

profile 1 #pid profile
set dterm_lpf_hz = 10
set d_boost_min =  1.000
set d_boost_max =  1.000
set fw_level_pitch_trim =  5.000
set roll_rate = 18
set pitch_rate = 9
set yaw_rate = 3
set fw_turn_assist_pitch_gain = 0.4
set max_angle_inclination_rll = 450
set fw_ff_pitch = 80
set fw_ff_roll = 50
set fw_p_pitch = 15
set fw_p_roll = 15

profile 2
set dterm_lpf_hz = 60
set dterm_lpf_type = PT3
set d_boost_min =  0.800
set d_boost_max =  1.200
set d_boost_gyro_delta_lpf_hz = 60
set antigravity_gain =  2.000
set antigravity_accelerator =  5.000
set smith_predictor_delay =  1.500
set tpa_rate = 20
set tpa_breakpoint = 1200
set tpa_on_yaw = ON #If model using control surface/tilt mechanism for stabilization in MC mode
set roll_rate = 18
set pitch_rate = 18
set yaw_rate = 9
set mc_iterm_relax = RPY

save

STEP1&2: Configuring as a Normal fixed-wing/Multi-Copter in two profiles separately

Select the fisrt Mixer Profile and PID Profile:

  • In the CLI, switch to the mixer_profile and pid_profile you wish to set first. You can also switch mixer_profile/pid_profile through gui if with aforementioned presets loaded. mixer_profile 1 #in this example, we set profile 1 first set mixer_pid_profile_linking = ON # Let the mixer_profile handle the pid_profile switch on this mixer_profile set platform_type = AIRPLANE save
  1. Configure the fixed-wing/Multi-Copter:
    • Configure your fixed-wing/Multi-Copter as you normally would, or you can copy and paste default settings to expedite the process.
    • Dshot esc protocol availability might be limited depends on outputs and fc board you are using. change the motor wiring or use oneshot/multishot esc protocol and calibrate throttle range.
    • You can use throttle = -1 as a placeholder for the motor you wish to stop if the motor isn’t the last motor
    • Consider conducting a test flight to ensure that everything operates as expected. And tune the settings, trim the servos.
Alt text
  1. Switch to Another Mixer Profile with PID Profile:
    • In the CLI, switch to another mixer_profile along with the appropriate pid_profile. You can also switch mixer_profile/pid_profile through gui if with aforementioned presets loaded. mixer_profile 2 set mixer_pid_profile_linking = ON set platform_type = MULTIROTOR/TRICOPTER save
  2. Configure the Multi-Copter/fixed-wing:
    • Set up your multi-copter/fixed-wing as usual, this time for mixer_profile 2 and pid_profile 2.
    • Utilize the ‘MAX’ input in the servo mixer to tilt the motors without altering the servo midpoint.
    • At this stage, focus on configuring profile-specific settings. You can streamline this process by copying and pasting the default PID settings.
    • you can set -1 in motor mixer throttle as a place holder: disable that motor but will load following motor rules
    • compass is required to enable navigation modes for multi-rotor profile.
    • Consider conducting a test flight to ensure that everything operates as expected. And tune the settings.
    • It is advisable to have a certain degree of control surface (elevon / elevator) mapping for stabilization even in multi-copter mode. This helps improve control authority when airspeed is high. It might be unable to recover from a dive without them.
Alt text
  1. Tailsitters:planned for INAV 7.1
    • Configure the fixed-wing mode/profile sets normally. Use MultiCopter platform type for tail_sitting flying mode/profile sets.
    • The baseline board aliment is FW mode(ROLL axis is the trust axis). So set tailsitter_orientation_offset = ON in the tail_sitting MC mode.
    • Configure mixer ROLL/YAW mixing according to tail_sitting orientation in the tail_sitting MC mode. YAW axis is the trust axis.
    • Conduct a bench test and see the orientation of the model changes in inav-configurator setup tab

STEP3: Mode Tab Settings:

We recommend using an 3-pos switch on you radio to activate these modes, So pilot can jump in or bell out at any moment.

Here is a example, in the bottom of inav-configurator Modes tab:

Alt text
1000~13001300~17001700~2000
Profile1(FW) with transition offProfile2(MC) with transition onProfile2(MC) with transition off
  • Profile file switching becomes available after completing the runtime sensor calibration(15-30s after booting). And It is not available when a navigation mode or position hold is active.
  • By default, mixer_profile 1 is used. mixer_profile 2 is used when the MIXER PROFILE 2 mode is activate. Once configured successfully, you will notice that the profiles and model preview changes accordingly when you refresh the relevant INAV Configurator tabs.
  • Use the MIXER TRANSITION mode to gain airspeed in MC profile, set MIXER TRANSITION accordingly.

Conduct a bench test on the model (without props attached). The model can now switch between fixed-wing and multi-copter modes while armed. Furthermore, it is capable of mid-air switching, resulting in an immediate stall upon entering fixed-wing profile

STEP4: Transition Mixing (Multi-Rotor Profile)(Recommended)

Transition Mixing is typically useful in multi-copter profile to gain airspeed in prior to entering the fixed-wing profile. When the MIXER TRANSITION mode is activated, the associated motor or servo will move according to your configured Transition Mixing.

Please note that transition input is disabled when a navigation mode is activated. The use of Transition Mixing is necessary to enable additional features such as VTOL RTH with out stalling.

Servo ‘Transition Mixing’: Tilting rotor configuration.

Add new servo mixer rules, and select ‘Mixer Transition’ in input. Set the weight/rate according to your desired angle. This will allow tilting the motor for tilting rotor model.

Alt text

Motor ‘Transition Mixing’: Dedicated forward motor configuration

In motor mixer set:

  • -2.0 < throttle < -1.0: The motor will spin regardless of the radio’s throttle position at a speed of abs(throttle) - 1 multiplied by throttle range only when Mixer Transition is activated.
Alt text

TailSitter ‘Transition Mixing’:

No additional settings needed, 45deg off set will be added to target pitch angle for angle mode in the firmware.

With aforementioned settings, your model should be able to enter fixed-wing profile without stalling.

Automated Switching (RTH) (Optional):

This is one of the least tested features. This feature is primarily designed for Return to Home (RTH) in the event of a failsafe.

When configured correctly, the model will use the Fixed-Wing (FW) mode to efficiently return home and then transition to Multi-Copter (MC) mode for easier landing.

To enable this feature, type following command in cli

  1. In your MC mode mixer profile (e.g., mixer_profile 2), set mixer_automated_switch to ON. leave it to OFF if burning remaining battery capacity on the way home is acceptable.
mixer_profile 2or1
set mixer_automated_switch= ON
  1. Set mixer_switch_trans_timer ds in cli in the MC mode mixer profile to specify the time required for your model to gain sufficient airspeed before transitioning to FW mode.
mixer_profile 2or1
set mixer_switch_trans_timer = 30 # 3s, 3000ms
  1. In your FW mode mixer profile (e.g., mixer_profile 1), also set mixer_automated_switch to ON. leave it to OFF if automated landing in fixed-wing is acceptable.
mixer_profile 1or2
set mixer_automated_switch = ON
  1. Save your settings. type save in cli.

If you set mixer_automated_switch to OFF for all mixer profiles (the default setting), the model will not perform automated transitions. You can always enable navigation modes after performing a manual transition.

Notes and Experiences

General

  • VTOL model operating in multi-copter (MC) mode may encounter challenges in windy conditions. Please exercise caution when testing in such conditions.
  • Make sure you can recover from a complete stall before trying the mid air transition
  • It will be much safer if you can understand every line in diff all, read your diff all before maiden

Tilting-rotor

  • In some tilting motor models, you may experience roll/yaw coupled oscillations when MIXER TRANSITION is activated. To address this issue, you can try the following:
    1. Use prop blade meets at top/rear prop direction for tilting motors to balance the effects of torque and P-factor.
    2. In addition to 1. Add a little yaw mixing(about 0.2) in tilt motors.
  • There will be a time window that tilting motors is providing up lift but rear motor isn’t. Result in a sudden pitch raise on the entering of the mode. Use the max speed or faster speed in tiling servo to reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect.

Dedicated forward motor

  • Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight

MixerProfile

A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings. It is designed for experienced inav users.

For a tutorial of vtol setup, Read https://github.com/iNavFlight/inav/blob/master/docs/VTOL.md

Not limited to VTOL. air/land/sea mixed vehicle is also achievable with this feature. Model behaves according to current mixer_profile’s platform_type and configured custom motor/servo mixer

Currently two profiles are supported on targets other than F411(due to resource constraints on F411). i.e VTOL transition is not available on F411.

For VTOL setup. one mixer_profile is used for multi-rotor(MR) and the other is used for fixed-wing(FW) By default, switching between profiles requires reboot to take affect. However, using the RC mode: MIXER PROFILE 2 will allow in flight switching for things like VTOL operation . And will re-initialize pid and navigation controllers for current MC or FW flying mode.

Please note that this is an emerging / experimental capability that will require some effort by the pilot to implement.

Mixer Transition input

Typically, ‘transition input’ will be useful in MR mode to gain airspeed. The associated motor or servo will then move accordingly when transition mode is activated. Transition input is disabled when navigation mode is activate

The use of Transition Mode is recommended to enable further features and future developments like fail-safe support. Mapping motor to servo output, or servo with logic conditions is not recommended

Servo

Mixer Transition is the input source for transition input; use this to tilt motor to gain airspeed.

Example: Increase servo 1 output by +45 with speed of 150 when transition mode is activated for tilted motor setup:

# rule no; servo index; input source; rate; speed; activate logic function number
smix 6 1 38 45 150 -1

Motor

The default mmix throttle value is 0.0, It will not show in diff command when throttle value is 0.0 (unused);

  • 0.0<throttle<=1.0 : normal mapping
  • -1.0<throttle<=0.0 : motor stop, default value 0, set to -1 to use a place holder for subsequent motor rules
  • -2.0<throttle<-1.0 : spin regardless of throttle position at speed abs(throttle)-1 when Mixer Transition is activated.

Airmode type should be set to “STICK_CENTER”. Airmode type must NOT be set to “THROTTLE_THRESHOLD”. If set to throttle threshold the (-) motor will spin till throttle threshold is passed.

Example: This will spin motor number 5 (counting from 1) at 20%, in transition mode only, to gain speed for a “4 rotor 1 pusher” setup:

# motor number; throttle; roll; pitch; yaw
mmix 4 -1.200  0.000  0.000  0.000

RC mode settings

It is recommend that the pilot uses a RC mode switch to activate modes or switch profiles. Profile files Switching is not available until the runtime sensor calibration is done. Switching is NOT available when navigation mode is activate.

mixer_profile 1 will be used as default, mixer_profile 2 will be used when the MIXER PROFILE 2 mode box is activated. Set MIXER TRANSITION accordingly when you want to use MIXER TRANSITION input for motors and servos. Here is sample of using these RC modes:

Alt text
1000~13001300~17001700~2000
FW(profile1) with transition offMC(profile2) with transition onMC(profile2) with transition off

It is also possible to set it as 4 state switch by adding FW(profile1) with transition on.

Automated Transition

This feature is mainly for RTH in a failsafe event. When set properly, model will use the FW mode to fly home efficiently, And land in the MC mode for easier landing. ON for a mixer_profile`s mixer_automated_switch means to schedule a Automated Transition when RTH head home(applies for MC mixer_profile) or RTH Land(applies for FW mixer_profile) is requested by navigation controller. Set mixer_automated_switch to ON in mixer_profile for MC mode. Set mixer_switch_trans_timer in mixer_profile for MC mode for the time required to gain airspeed for your model before entering to FW mode. When mixer_automated_switch:OFF is set for all mixer_profiles(defaults). Model will not perform automated transition at all.

TailSitter (planned for INAV 7.1)

TailSitter is supported by add a 90deg offset to the board alignment. Set the board aliment normally in the mixer_profile for FW mode(set platform_type = AIRPLANE), The motor trust axis should be same direction as the airplane nose. Then, in the mixer_profile for takeoff and landing set tailsitter_orientation_offset = ON to apply orientation offset. orientation offset will also add a 45deg orientation offset.

Parameter list (Partial List)

Please be aware of what parameter is shared among FW/MC modes and what isn’t.

Shared Parameters

  • Timer Overrides
  • Outputs [Servo]:
    • Servo min-point, mid-point, max-point settings
  • Motor Configuration:
    • motor_pwm_protocol
    • motor_poles
  • Servo Configuration:
    • servo_protocol
    • servo_pwm_rate
  • Board Alignment
  • ·······

Profile-Specific Parameters in VTOL

  • Mixer Profile
    • Mixer Configuration:
      • platform_type
      • motor_stop_on_low
      • tailsitter_orientation_offset
      • motor_direction_inverted, and more·······
    • Motor Mixing (mmix)
    • Servo Mixing (smix)
  • PID Profile
    • PIDs for Roll, Pitch, Yaw
    • PIDs for Navigation Modes
    • TPA (Throttle PID Attenuation) Settings
    • Rate Settings
    • ·······

TailSitter support

TailSitter is supported by add a 90deg offset to the board alignment. Set the board aliment normally in the mixer_profile for FW mode(set platform_type = AIRPLANE), The motor trust axis should be same direction as the airplane nose. Then, in the mixer_profile for takeoff and landing set platform_type = TAILSITTER. The TAILSITTER platform type is same as MULTIROTOR platform type, expect for a 90 deg board alignment offset. In TAILSITTER mixer_profile, when motor trust/airplane nose is pointing to the sky, ‘airplane bottom’/’multi rotor front’ should facing forward in model preview. Set the motor/servo mixer according to multirotor orientation, Model should roll around geography’s longitudinal axis, the roll axis of TAILSITTER will be yaw axis of AIRPLANE. In addition, When MIXER TRANSITION input is activated, a 45deg offset will be add to the target angle for angle mode.

Happy flying

Remember that this is currently an emerging capability:

  • Test every thing on bench first.
  • Try MR or FW mode separately see if there are any problems.
  • Use the INAV Discord for help and setup questions; use the Github Issues for reporting bugs and unexpected behaviors. For reporting on Github, a CLI diff all, a DVR and a Blackbox log of the incident will assist investigation.
Table of Contents