mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
* lib: add FilteredDerivative class * AirspeedValidator: add first principle check - filters throttle, pitch and airspeed rate, and triggers if the airspeed rate is negative even though the vehicle is pitching down and giving high throttle. Check has to fail for duration defined by ASPD_FP_T_WINDOW to trigger an airspeed failure. * AirspeedValidator: define constants for first principle check * FilteredDerivative: set initialised to false if sample interval is invalid * airspeed_selector: improved comment * increase IAS derivative filter time constant from 4 to 5 * use legacy parameter handling for FW_PSP_OFF * handle FW_THR_MAX as well * ROMFS/airframes: exclude some airframes for v6x and v4pro to save flash on them --------- Signed-off-by: Silvan Fuhrer <silvan@auterion.com> Signed-off-by: RomanBapst <bapstroman@gmail.com> Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
96 lines
2.2 KiB
Bash
96 lines
2.2 KiB
Bash
#!/bin/sh
|
|
#
|
|
# @name UVify IFO
|
|
#
|
|
# @type Quadrotor x
|
|
# @class Copter
|
|
#
|
|
# @maintainer Hyon Lim <lim@uvify.com>
|
|
#
|
|
# @board px4_fmu-v2 exclude
|
|
# @board px4_fmu-v3 exclude
|
|
# @board px4_fmu-v4pro exclude
|
|
# @board px4_fmu-v5 exclude
|
|
# @board px4_fmu-v5x exclude
|
|
# @board px4_fmu-v6x exclude
|
|
# @board bitcraze_crazyflie exclude
|
|
# @board cuav_x7pro exclude
|
|
#
|
|
|
|
. ${R}etc/init.d/rc.mc_defaults
|
|
|
|
# Attitude & rate gains
|
|
param set-default MC_ROLLRATE_D 0.0013
|
|
param set-default MC_PITCHRATE_D 0.0016
|
|
|
|
param set-default MPC_MANTHR_MAX 0.9
|
|
|
|
# Filter settings
|
|
param set-default IMU_DGYRO_CUTOFF 90
|
|
param set-default IMU_GYRO_CUTOFF 100
|
|
|
|
# System
|
|
|
|
param set-default SENS_BOARD_ROT 10
|
|
|
|
# EKF2
|
|
param set-default EKF2_GND_EFF_DZ 6
|
|
|
|
# Position control
|
|
param set-default MPC_Z_VEL_I_ACC 0.4
|
|
|
|
param set-default MPC_THR_MIN 0.06
|
|
param set-default MPC_THR_HOVER 0.3
|
|
|
|
param set-default MIS_TAKEOFF_ALT 1.1
|
|
param set-default MPC_XY_P 1.7
|
|
param set-default MPC_XY_VEL_P_ACC 2.6
|
|
param set-default MPC_XY_VEL_I_ACC 1.2
|
|
param set-default MPC_TKO_RAMP_T 1
|
|
param set-default MPC_VEL_MANUAL 3
|
|
|
|
param set-default BAT1_SOURCE 0
|
|
param set-default BAT1_N_CELLS 4
|
|
param set-default BAT1_V_DIV 10.14
|
|
param set-default BAT1_A_PER_V 18.18
|
|
|
|
# Filter settings
|
|
param set-default IMU_GYRO_CUTOFF 90
|
|
param set-default IMU_DGYRO_CUTOFF 70
|
|
|
|
# Don't try to be intelligent on RC loss: just cut the motors
|
|
param set-default NAV_RCL_ACT 6
|
|
|
|
# TELEM1 ttyS1 - Wifi module
|
|
param set-default MAV_0_CONFIG 101
|
|
param set-default MAV_0_RATE 0
|
|
# onboard
|
|
param set-default MAV_0_MODE 2
|
|
param set-default SER_TEL1_BAUD 921600
|
|
|
|
# TELEM2 ttyS2 - Sub 1-Ghz
|
|
param set-default MAV_1_CONFIG 102
|
|
# normal
|
|
param set-default MAV_1_MODE 0
|
|
param set-default SER_TEL2_BAUD 57600
|
|
|
|
param set-default PWM_MAIN_TIM0 0
|
|
|
|
# Square quadrotor X PX4 numbering
|
|
param set-default CA_ROTOR_COUNT 4
|
|
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 PWM_MAIN_FUNC1 101
|
|
param set-default PWM_MAIN_FUNC2 102
|
|
param set-default PWM_MAIN_FUNC3 103
|
|
param set-default PWM_MAIN_FUNC4 104
|