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.

148 lines
0 B

#!/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
#
# @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 intel_aerofc-v1 exclude
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
#
# @maintainer Hyon Lim <lim@uvify.com>
#
sh /etc/init.d/rc.mc_defaults
set MIXER hexa_x
set PWM_OUT 12345678
if [ $AUTOCNF = yes ]
then
###############################################
# Attitude & rate gains
###############################################
# Roll
param set MC_ROLL_P 6.50000
param set MC_ROLLRATE_P 0.15000
param set MC_ROLLRATE_I 0.05000
param set MC_ROLLRATE_D 0.00130
param set MC_ROLLRATE_MAX 800.00000
# Pitch
param set MC_PITCH_P 6.50000
param set MC_PITCHRATE_P 0.15000
param set MC_PITCHRATE_I 0.05000
param set MC_PITCHRATE_D 0.00160
param set MC_PITCHRATE_MAX 800.00000
# Yaw
param set MC_YAW_P 2.80000
param set MC_YAWRATE_P 0.20000
param set MC_YAWRATE_I 0.10000
param set MC_YAWRATE_D 0.00000
param set MC_YAW_FF 0.00000
param set MC_YAWRATE_MAX 700.00000
###############################################
# Multirotor Position Gains
###############################################
param set MPC_ACC_HOR 8.0000
param set MPC_THR_MIN 0.06000
param set MPC_THR_HOVER 0.3000
# altitude control gains
param set MPC_Z_P 1.00000
param set MPC_Z_VEL_P 0.20000
param set MPC_Z_VEL_I 0.02000
param set MPC_Z_VEL_D 0.00000
# position control gains
param set MPC_XY_P 0.9500
param set MPC_XY_VEL_P 0.0900
param set MPC_XY_VEL_I 0.0200
param set MPC_XY_VEL_D 0.0100
# etc gains
param set MPC_TKO_RAMP_T 0.4000
param set MPC_TKO_SPEED 1.5000
param set MPC_VEL_MANUAL 5.0000
# Disable RC filtering
param set RC_FLT_CUTOFF 0.00000
# Filter settings
param set MC_DTERM_CUTOFF 90.00000
param set IMU_GYRO_CUTOFF 100.00000
# Thrust curve (avoids the need for TPA)
param set THR_MDL_FAC 0.25
# System
param set PWM_MAX 1950
param set PWM_MIN 1100
param set PWM_MAIN_DIS5 980
param set PWM_MAIN_DIS6 980
# DSHOT
param set DSHOT_CONFIG 600
param set COM_ARM_MAG 0.2000
param set MIS_TAKEOFF_ALT 1.1000
#####################################
# EKF
#####################################
# Height mode as GPS
param set EKF2_HGT_MODE 1
# Enable optical flow and GPS
param set EKF2_AID_MASK 1
param set EKF2_RNG_AID 1
param set EKF2_MAG_TYPE 1
param set EKF2_OF_QMIN 80.0000
# default horizontal stablization sensors
param set SENS_EN_PMW3901 1
param set SENS_EN_PX4FLOW 1
param set SENS_EN_LL40LS 2
param set SENS_FLOW_ROT 2
#
param set CBRK_IO_SAFETY 22027
param set COM_DISARM_LAND 3
# PWM ONESHOT
param set PWM_RATE 0
# Battery
param set BAT_SOURCE 0
param set BAT_N_CELLS 4
param set BAT_V_DIV 10.133
# TELEM1 ttyS1
param set MAV_0_CONFIG 101
param set MAV_0_MODE 0 # onboard
param set MAV_0_FORWARD 1
param set SER_TEL1_BAUD 57600
# TELEM2 ttyS2
param set MAV_1_CONFIG 102
param set MAV_1_MODE 2
param set MAV_1_FORWARD 1
param set MAV_1_RATE 800000
param set SER_TEL2_BAUD 921600
# Disable internal magnetometer sensor
param set CAL_MAG0_EN 0
# Enable external magnetometer sensor
param set CAL_MAG1_EN 1
fi