You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
125 lines
3.0 KiB
125 lines
3.0 KiB
#!/bin/sh |
|
# |
|
# @name UVify Draco-R |
|
# |
|
# @type Hexarotor x |
|
# @class Copter |
|
# |
|
# @output MAIN1 motor 1 |
|
# @output MAIN2 motor 2 |
|
# @output MAIN3 motor 3 |
|
# @output MAIN4 motor 4 |
|
# @output MAIN5 motor 5 |
|
# @output MAIN6 motor 6 |
|
# |
|
# @output AUX1 feed-through of RC AUX1 channel |
|
# @output AUX2 feed-through of RC AUX2 channel |
|
# |
|
# @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_P 1 |
|
param set-default MPC_Z_VEL_P_ACC 4 |
|
param set-default MPC_Z_VEL_I_ACC 0.4 |
|
# position control gains |
|
param set-default MPC_XY_P 0.9500 |
|
param set-default MPC_XY_VEL_P_ACC 1.8 |
|
param set-default MPC_XY_VEL_I_ACC 0.4 |
|
param set-default MPC_XY_VEL_D_ACC 0.2 |
|
# 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_MIN 1100 |
|
param set-default PWM_MAIN_DIS5 980 |
|
param set-default PWM_MAIN_DIS6 980 |
|
|
|
# DSHOT |
|
param set-default DSHOT_CONFIG 600 |
|
|
|
param set-default MIS_TAKEOFF_ALT 1.1 |
|
|
|
##################################### |
|
# EKF |
|
##################################### |
|
# Height mode as GPS |
|
param set-default EKF2_HGT_MODE 1 |
|
# 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 CBRK_IO_SAFETY 22027 |
|
param set-default COM_DISARM_LAND 3 |
|
|
|
# PWM ONESHOT |
|
param set-default PWM_MAIN_RATE 0 |
|
|
|
# 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 |
|
|
|
|
|
set MIXER hexa_x |
|
set PWM_OUT 12345678
|
|
|