mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
124 lines
3.2 KiB
Bash
124 lines
3.2 KiB
Bash
#!/bin/sh
|
|
#
|
|
# @name UVify Draco-R
|
|
#
|
|
# @type Hexarotor 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 bitcraze_crazyflie exclude
|
|
#
|
|
|
|
. ${R}etc/init.d/rc.mc_defaults
|
|
|
|
# MAV_TYPE_HEXAROTOR 13
|
|
param set-default MAV_TYPE 13
|
|
|
|
###############################################
|
|
# Attitude & rate gains
|
|
###############################################
|
|
# Roll
|
|
param set-default MC_ROLLRATE_I 0.05
|
|
param set-default MC_ROLLRATE_D 0.0013
|
|
param set-default MC_ROLLRATE_MAX 800
|
|
# Pitch
|
|
param set-default MC_PITCHRATE_I 0.05
|
|
param set-default MC_PITCHRATE_D 0.0016
|
|
param set-default MC_PITCHRATE_MAX 800
|
|
# Yaw
|
|
param set-default MC_YAWRATE_MAX 700
|
|
|
|
###############################################
|
|
# Multirotor Position Gains
|
|
###############################################
|
|
param set-default MPC_ACC_HOR 8
|
|
param set-default MPC_THR_MIN 0.06
|
|
param set-default MPC_THR_HOVER 0.3
|
|
# altitude control gains
|
|
param set-default MPC_Z_VEL_I_ACC 0.4
|
|
# position control gains
|
|
# etc gains
|
|
param set-default MPC_TKO_RAMP_T 0.4
|
|
param set-default MPC_VEL_MANUAL 5
|
|
|
|
# Filter settings
|
|
param set-default IMU_DGYRO_CUTOFF 90
|
|
param set-default IMU_GYRO_CUTOFF 100
|
|
|
|
# Thrust curve (avoids the need for TPA)
|
|
param set-default THR_MDL_FAC 0.25
|
|
|
|
# System
|
|
param set-default PWM_MAIN_DIS5 980
|
|
param set-default PWM_MAIN_DIS6 980
|
|
|
|
param set-default MIS_TAKEOFF_ALT 1.1
|
|
|
|
#####################################
|
|
# EKF
|
|
#####################################
|
|
# Enable optical flow and GPS
|
|
param set-default EKF2_MAG_TYPE 1
|
|
param set-default EKF2_OF_QMIN 80
|
|
|
|
# default horizontal stablization sensors
|
|
param set-default SENS_EN_PMW3901 1
|
|
param set-default SENS_EN_PX4FLOW 1
|
|
param set-default SENS_EN_LL40LS 2
|
|
param set-default SENS_FLOW_ROT 2
|
|
|
|
param set-default COM_DISARM_LAND 3
|
|
|
|
# Battery
|
|
param set-default BAT1_SOURCE 0
|
|
param set-default BAT1_N_CELLS 4
|
|
param set-default BAT1_V_DIV 10.133
|
|
|
|
# TELEM1 ttyS1
|
|
param set-default MAV_0_CONFIG 101
|
|
param set-default MAV_0_MODE 0
|
|
param set-default MAV_0_FORWARD 1
|
|
param set-default SER_TEL1_BAUD 57600
|
|
|
|
# TELEM2 ttyS2
|
|
param set-default MAV_1_CONFIG 102
|
|
param set-default MAV_1_MODE 2
|
|
param set-default MAV_1_FORWARD 1
|
|
param set-default MAV_1_RATE 800000
|
|
param set-default SER_TEL2_BAUD 921600
|
|
|
|
|
|
param set-default CA_ROTOR_COUNT 6
|
|
param set-default CA_ROTOR0_PX 0
|
|
param set-default CA_ROTOR0_PY 0.5
|
|
param set-default CA_ROTOR0_KM -0.05
|
|
param set-default CA_ROTOR1_PX 0
|
|
param set-default CA_ROTOR1_PY -0.5
|
|
param set-default CA_ROTOR2_PX 0.43
|
|
param set-default CA_ROTOR2_PY -0.25
|
|
param set-default CA_ROTOR2_KM -0.05
|
|
param set-default CA_ROTOR3_PX -0.43
|
|
param set-default CA_ROTOR3_PY 0.25
|
|
param set-default CA_ROTOR4_PX 0.43
|
|
param set-default CA_ROTOR4_PY 0.25
|
|
param set-default CA_ROTOR5_PX -0.43
|
|
param set-default CA_ROTOR5_PY -0.25
|
|
param set-default CA_ROTOR5_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
|
|
param set-default PWM_MAIN_FUNC5 105
|
|
param set-default PWM_MAIN_FUNC6 106
|
|
|
|
param set-default PWM_MAIN_TIM0 -1
|
|
param set-default PWM_MAIN_TIM1 -1
|
|
param set-default PWM_MAIN_TIM2 -1
|