Adding a Frame Configuration
PX4 frame configuration files are shell scripts that set up some (or all) of the parameters, controllers and apps needed for a particular vehicle frame, such as a quadcopter, ground vehicle, or boat. These scripts are executed when the corresponding airframe is selected and applied in QGroundControl.
The configuration files that are compiled into firmware for NuttX targets are located in the ROMFS/px4fmu_common/init.d folder (configuration files for POSIX simulators are stored in ROMFS/px4fmu_common/init.d-posix). Папка містить як повні конфігурації для конкретних транспортних засобів, так і часткові "загальні конфігурації" для різних типів транспортних засобів. Загальні конфігурації часто використовуються як вихідна точка для створення нових файлів конфігурації.
Додатково, файл конфігурації рами також може бути завантажений з SD-карти.
INFO
You can also "tweak" the current frame configuration using text files on the SD card. This is covered in System Startup > Customizing the System Startup page.
INFO
To determine which parameters/values need to be set in the configuration file, you can first assign a generic airframe and tune the vehicle, and then use param show-for-airframe
to list the parameters that changed.
Налаштування кадру в розробці
Рекомендований процес розробки нової конфігурації кадру:
- Start by selecting an appropriate "generic configuration" for the target vehicle type in QGC, such as Generic Quadcopter.
- Configure the geometry and actuator outputs.
- Perform other basic configuration.
- Налаштуйте транспортний засіб.
- Run the
param show-for-airframe
console command to list the parameter difference compared to the original generic airfame.
Після того, як ви маєте параметри, ви можете створити новий файл конфігурації рами, скопіювавши файл конфігурації для загальної конфігурації та додавши нові параметри.
Alternatively you can just append the modified parameters to the startup configuration files described in System Startup > Customizing the System Startup ("tweaking the generic configuration").
Як додати конфігурацію до прошивки
Як додати конфігурацію до прошивки:
- Create a new config file in the init.d/airframes folder.
- Give it a short descriptive filename and prepend the filename with an unused autostart ID (for example,
1033092_superfast_vtol
). - Оновіть файл з параметрами конфігурації та програмами (див. вище).
- Give it a short descriptive filename and prepend the filename with an unused autostart ID (for example,
- Add the name of the new frame config file to the CMakeLists.txt in the relevant section for the type of vehicle
- Build and upload the software.
Як додати конфігурацію на SD-карту
Файл конфігурації рами, що буде запущений з SD-карти, такий самий, як той, що зберігається в прошивці.
To make PX4 launch with a frame configuration, renamed it to rc.autostart
and copy it to the SD card at /ext_autostart/rc.autostart
. PX4 знайде будь-які пов’язані файли у мікропрограмі.
Огляд файлу конфігурації
Файл конфігурації складається з кількох основних блоків:
- Documentation (used in the Airframes Reference and QGroundControl). Специфічні налаштування параметрів планера
- The configuration and geometry using control allocation parameters
- Tuning gains
- Контролери та програми, які мають запускатися, такі як контролери багатороторників або фіксованих крил, детектори посадки та інше.
Ці аспекти в основному незалежні, що означає, що багато конфігурацій використовують ту саму фізичну конструкцію літального апарату, запускають ті ж самі додатки і відрізняються переважно у своїх налаштуваннях.
INFO
New frame configuration files are only automatically added to the build system after a clean build (run make clean
).
Приклад - загальна конфігурація рами квадрокоптера
The configuration file for a generic Quad X copter is shown below (original file here). Це дуже просто, оскільки воно визначає лише мінімальні налаштування, загальні для всіх квадрокоптерів.
Перший рядок — це shebang, який повідомляє операційній системі NuttX (на якій працює PX4), що файл конфігурації є виконуваним сценарієм оболонки.
c
#!/bin/sh
Далі йде кадрова документація. The @name
, @type
and @class
are used to identify and group the frame in the API Reference and QGroundControl Airframe Selection.
plain
# @name Generic Quadcopter
#
# @type Quadrotor x
# @class Copter
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
The next line imports generic parameters that are appropriate for all vehicles of the specified type (see init.d/rc.mc_defaults).
plain
. ${R}etc/init.d/rc.mc_defaults
Finally the file lists the control allocation parameters (starting with CA_
that define the default geometry for the frame. These may be modified for your frame geometry in the Actuators Configuration, and output mappings may be added.
sh
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
param set-default CA_ROTOR0_PY 0.15
param set-default CA_ROTOR1_PX -0.15
param set-default CA_ROTOR1_PY -0.15
param set-default CA_ROTOR2_PX 0.15
param set-default CA_ROTOR2_PY -0.15
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.15
param set-default CA_ROTOR3_PY 0.15
param set-default CA_ROTOR3_KM -0.05
Приклад – Повний транспортний засіб Babyshark VTOL
Нижче наведено більш складний файл конфігурації для повного транспортного засобу. This is the configuration for the Baby Shark Standard VTOL (original file here).
The shebang and documentation sections are similar to those for the generic frame, but here we also document what outputs
are mapped to each motor and actuator. Зверніть увагу, що ці результати є лише документацією; фактичне відображення виконується за допомогою параметрів.
sh
#!/bin/sh
#
# @name BabyShark VTOL
#
# @type Standard VTOL
# @class VTOL
#
# @maintainer Silvan Fuhrer <silvan@auterion.com>
#
# @output Motor1 motor 1
# @output Motor2 motor 2
# @output Motor3 motor 3
# @output Motor4 motor 4
# @output Motor5 Pusher motor
# @output Servo1 Ailerons
# @output Servo2 A-tail left
# @output Servo3 A-tail right
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
# @board holybro_kakutef7 exclude
#
Як і для загальної конструкції, ми додаємо типові значення VTOL за замовчуванням.
sh
. ${R}etc/init.d/rc.vtol_defaults
Then we define configuration parameters and tuning gains:
sh
param set-default MAV_TYPE 22
param set-default BAT1_N_CELLS 6
param set-default FW_AIRSPD_MAX 30
param set-default FW_AIRSPD_MIN 19
param set-default FW_AIRSPD_TRIM 23
param set-default FW_PN_R_SLEW_MAX 40
param set-default FW_PSP_OFF 3
param set-default FW_P_LIM_MAX 18
param set-default FW_P_LIM_MIN -25
param set-default FW_RLL_TO_YAW_FF 0.1
param set-default FW_RR_P 0.08
param set-default FW_R_LIM 45
param set-default FW_R_RMAX 50
param set-default FW_THR_TRIM 0.65
param set-default FW_THR_MIN 0.3
param set-default FW_THR_SLEW_MAX 0.6
param set-default FW_T_HRATE_FF 0
param set-default FW_T_SINK_MAX 15
param set-default FW_T_SINK_MIN 3
param set-default FW_YR_P 0.15
param set-default IMU_DGYRO_CUTOFF 15
param set-default MC_PITCHRATE_MAX 60
param set-default MC_ROLLRATE_MAX 60
param set-default MC_YAWRATE_I 0.15
param set-default MC_YAWRATE_MAX 40
param set-default MC_YAWRATE_P 0.3
param set-default MPC_ACC_DOWN_MAX 2
param set-default MPC_ACC_HOR_MAX 2
param set-default MPC_ACC_UP_MAX 3
param set-default MC_AIRMODE 1
param set-default MPC_JERK_AUTO 4
param set-default MPC_LAND_SPEED 1
param set-default MPC_MAN_TILT_MAX 25
param set-default MPC_MAN_Y_MAX 40
param set-default COM_SPOOLUP_TIME 1.5
param set-default MPC_THR_HOVER 0.45
param set-default MPC_TILTMAX_AIR 25
param set-default MPC_TKO_RAMP_T 1.8
param set-default MPC_TKO_SPEED 1
param set-default MPC_VEL_MANUAL 3
param set-default MPC_XY_CRUISE 3
param set-default MPC_XY_VEL_MAX 3.5
param set-default MPC_YAWRAUTO_MAX 40
param set-default MPC_Z_VEL_MAX_UP 2
param set-default NAV_ACC_RAD 3
param set-default SENS_BOARD_ROT 4
param set-default VT_ARSP_BLEND 10
param set-default VT_ARSP_TRANS 21
param set-default VT_B_DEC_MSS 1.5
param set-default VT_B_TRANS_DUR 12
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_FWD_THRUST_SC 1.2
param set-default VT_F_TR_OL_TM 8
param set-default VT_PSHER_SLEW 0.5
param set-default VT_TRANS_MIN_TM 4
param set-default VT_TYPE 2
Нарешті, файл визначає параметри розподілу керування для геометрії та параметри, які встановлюють відповідність виходів різним двигунам та сервоприводам.
sh
param set-default CA_AIRFRAME 2
param set-default CA_ROTOR_COUNT 5
param set-default CA_ROTOR0_PX 1
param set-default CA_ROTOR0_PY 1
param set-default CA_ROTOR1_PX -1
param set-default CA_ROTOR1_PY -1
param set-default CA_ROTOR2_PX 1
param set-default CA_ROTOR2_PY -1
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -1
param set-default CA_ROTOR3_PY 1
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR4_AX 1.0
param set-default CA_ROTOR4_AZ 0.0
param set-default CA_SV_CS_COUNT 3
param set-default CA_SV_CS0_TYPE 15
param set-default CA_SV_CS0_TRQ_R 1.0
param set-default CA_SV_CS1_TRQ_P 0.5000
param set-default CA_SV_CS1_TRQ_R 0.0000
param set-default CA_SV_CS1_TRQ_Y -0.5000
param set-default CA_SV_CS1_TYPE 13
param set-default CA_SV_CS2_TRQ_P 0.5000
param set-default CA_SV_CS2_TRQ_Y 0.5000
param set-default CA_SV_CS2_TYPE 14
param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 202
param set-default PWM_MAIN_FUNC3 105
param set-default PWM_MAIN_FUNC4 203
param set-default PWM_MAIN_FUNC5 101
param set-default PWM_MAIN_FUNC6 102
param set-default PWM_MAIN_FUNC7 103
param set-default PWM_MAIN_FUNC8 104
param set-default PWM_MAIN_TIM0 50
param set-default PWM_MAIN_DIS1 1500
param set-default PWM_MAIN_DIS2 1500
param set-default PWM_MAIN_DIS3 1000
param set-default PWM_MAIN_DIS4 1500
Додавання нової групи планера
Airframe "groups" are used to group similar airframes for selection in QGroundControl and in the Airframe Reference. Кожна група має назву та пов'язаний з нею зображення у форматі Svg, яке показує загальну геометрію, кількість двигунів та напрямок обертання двигунів для повітряних каркасів, що належать до цієї групи.
The airframe metadata files used by QGroundControl and the documentation source code are generated from the airframe description, via a script, using the build command: make airframe_metadata
For a new frame belonging to an existing group, you don't need to do anything more than provide documentation in the airframe description located at ROMFS/px4fmu_common/init.d.
If the airframe is for a new group you additionally need to:
Add the svg image for the group into user guide documentation (if no image is provided a placeholder image is displayed): assets/airframes/types
Add a mapping between the new group name and image filename in the srcparser.py method
GetImageName()
(follow the pattern below):pythondef GetImageName(self): """ Get parameter group image base name (w/o extension) """ if (self.name == "Standard Plane"): return "Plane" elif (self.name == "Flying Wing"): return "FlyingWing" ... ... return "AirframeUnknown"
Update QGroundControl:
Add the svg image for the group into: src/AutopilotPlugins/Common/images
Add reference to the svg image into qgcimages.qrc, following the pattern below:
xml<qresource prefix="/qmlimages"> ... <file alias="Airframe/AirframeSimulation">src/AutoPilotPlugins/Common/Images/AirframeSimulation.svg</file> <file alias="Airframe/AirframeUnknown">src/AutoPilotPlugins/Common/Images/AirframeUnknown.svg</file> <file alias="Airframe/Boat">src/AutoPilotPlugins/Common/Images/Boat.svg</file> <file alias="Airframe/FlyingWing">src/AutoPilotPlugins/Common/Images/FlyingWing.svg</file> ...
INFO
The remaining airframe metadata should be automatically included in the firmware (once srcparser.py is updated).
:::
Підвищення налаштування
Наступні теми пояснюють, як налаштувати параметри, які будуть вказані у конфігураційному файлі:
- Autotuning (Multicopter) (or Multicopter PID Tuning Guide)
- Autotuning (Fixed-wing) (or Fixed-wing PID Tuning Guide)
- Autotuning (VTOL) (VTOL Configuration)
Додайте фрейм до QGroundControl
To make a new airframe available for section in the QGroundControl frame configuration:
- Make a clean build (e.g. by running
make clean
and thenmake px4_fmu-v5_default
) - Open QGC and select Custom firmware file... as shown below:
You will be asked to choose the .px4 firmware file to flash (this file is a zipped JSON file and contains the airframe metadata).
- Navigate to the build folder and select the firmware file (e.g. PX4-Autopilot/build/px4_fmu-v5_default/px4_fmu-v5_default.px4).
- Press OK to start flashing the firmware.
- Restart QGroundControl.
The new frame will then be available for selection in QGroundControl.