Auterion for Manufacturers
Latest Manufacturer's Guide
Search
K
Links
Comment on page

Airframe Setup in Software

Basic integration of the Skynode onto your own custom airframe

What is an airframe file?

In PX4 the airframe file does mainly two things:
  1. 1.
    Load pre-defined parameters: Pre-defining parameters is convenient for setting up a large number of the same aircrafts. This step is optional as parameters can also be set manually over AMC
  2. 2.
    Load mixer files: Mixer files specify the mapping of control inputs to motor and servo outputs. You need a mixer file which fits the geometry of your airframe before you can fly.

Check support for your airframe type

If the airframe geometry of your aircraft is common, it is likely that your airframe is already supported by an existing airframe file. The airframes supported by PX4 and to that extent Auterion Enterprise PX4 can be found in PX4's official documentation.
  • Your airframe is supported: In this case you do not need to write your own airframe file because mixer definitions for your airframe already exist. You can go ahead and mount your Skynode on your craft, then choose the correct airframe type in AMC and proceed to bench testing. You can later still integrate your custom parameter settings in your own airframe file to simplify the bring up of further units.
  • Your airframe is not supported: This means that no mixer definition for your airframe type exists. You have to write a custom mixer file and load it as part of a custom airframe file before you will be able to fly. Refer to the example below on how to proceed.

Example: Integration on an X500

For the sake of this example we will create and load a custom mixer for a quadrotor airframe, even though the Quadrotor configuration is a regular airframe already supported by PX4.

Writing a custom mixer file

Information about the structure and syntax of mixer files can be found in the official PX4 documentation.
Mixer files named .main.mix will be loaded to the IO controller which correspond to the PWM outputs on the secondary breakout board on Skynode.
Mixer files named .aux.mix will be loaded to the FMU controller which correspond to the PWM outputs on the primary breakout board on Skynode.
For the X500 airframe the mixer file could look like this:
x500.main.mix
R: 4x
AUX1 Passthrough
M: 1
S: 3 5 10000 10000 0 -10000 10000
AUX2 Passthrough
M: 1
S: 3 6 10000 10000 0 -10000 10000
Failsafe outputs
The following outputs are set to their disarmed value
during normal operation and to their failsafe falue in case
of flight termination.
Z:
Z:
Multirotor mixers require a specified geometry, in this case 4x. Supported geometries can be found in the open-source PX4 Firmware. Geometries specify the ratio of the motor placements on the airframe. If you cannot find a geometry which fits your airframe (e.g. if your aircraft is asymmetrical), please contact Auterion for support. Custom geometries are currently not supported as they are compiled as part of the Firmware.

Loading the custom mixer through an airframe file

A custom airframe file for the x500 could look like this:
1300001_x500
sh /etc/init.d/rc.mc_defaults
set MIXER x500
set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
# Sensor parameters
param set-default CAL_MAG1_ROT 30
fi
The name of your airframe file must be of the format <unique_id>_<name>, e.g. 1300001_x500. The unique_id will allow you to load the airframe later by setting the parameter SYS_AUTOSTART:param set SYS_AUTOSTART 1300001.

Getting your airframe file and mixer on Skynode

  1. 1.
  2. 2.
    Save your airframe file as aepx4-developer-tools-2.x.x/fmu/config/airframes/1300001_x500
  3. 3.
    Save your mixer definition file as
    aepx4-developer-tools-2.x.x/fmu/config/mixers/x500.main.mix
  4. 4.
    Edit the file rc.autostart under aepx4-developer-tools-2.x.x/fmu/config and add your custom airframe there:
    rc.autostart
    if param compare SYS_AUTOSTART 1300001
    then
    sh /fs/microsd/ext_autostart/airframes/1300001_x500
    fi
  5. 5.
    Download the newest Auterion Enterprise PX4 as a base image from the Auterion SuiteIf the previous vehicle owner, in this case Watts, flew the vehicle, you won't get that number because you don't have access to
  6. 6.
    Package your new image by executing
    cd aepx4-developer-tools-2.x.x
    make package-update version=x500-test artifactPath=<AEPX4 Release>.auterionos
  7. 7.
    You will find your new image under aepx4-developer-tools-2.x.x/output/update.auterionos Flash your Skynode with this new image as described in Software Update.
  8. 8.
    Wait for your Skynode to boot and connect to Auterion Mission Control. Change the parameter SYS_AUTOSTART = 1300001 and SYS_AUTOCONFIG = reset parameters to airframe defaults
  9. 9.
    Reboot your vehicle to perform the pa.
  10. 10.
    Check in the mavlink shell if your mixer was loaded correctly by entering the command dmesg. It should show a line like this:
    INFO [init] Mixer: /fs/microsd/ext_autostart/mixers/x500.aux.mix on /dev/pwm_output1
  11. 11.
    check you PWM settings with the following command:
    pwm info -d /dev/pwm_output1
    For servos the PWM rate should be 50Hz and the disarmed value around 1500ms
    For motors the PWM rate should be 400Hz and the disarmed value around 900ms.
    You can change the disarmed PWM value on a per channel basis by editing the parameters PWM_AUX_DIS* and PWM_MAIN_DIS* for the primary and secondary outputs. You can change the PWM rate over the parameters PWM_RATE and PWM_AUX_RATE
  12. 12.
    ATTENTION: REMOVE THE PROPELLERS BEFORE PROCEEDING
    Check if you motors and servos move correctly. These commands will make your servos and motors move by directly setting the PWM outputs. pwm test -d /dev/pwm_output1 -c 56 -p 2000 (to test servos) pwm test -d /dev/pwm_output1 -c 12 -p 2000 (to test motors)
If your motors do not spin at the same speed if you send them the same PWM signal you might need to calibrate your ESCs.