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.
119 lines
3.2 KiB
119 lines
3.2 KiB
#!/bin/sh |
|
# |
|
# @name PX4 Vision DevKit Platform |
|
# |
|
# @type Quadrotor x |
|
# @class Copter |
|
# |
|
# @output MAIN1 motor 1 |
|
# @output MAIN2 motor 2 |
|
# @output MAIN3 motor 3 |
|
# @output MAIN4 motor 4 |
|
# |
|
# @board px4_fmu-v2 exclude |
|
# @board bitcraze_crazyflie exclude |
|
# |
|
|
|
. ${R}etc/init.d/rc.mc_defaults |
|
|
|
# System parameters |
|
# use FMU motor outputs for less delay in the rate control loop |
|
param set-default SYS_USE_IO 0 |
|
|
|
# Commander Parameters |
|
param set-default COM_OBS_AVOID 1 |
|
param set-default COM_DISARM_LAND 0.5 |
|
|
|
# EKF2 parameters |
|
param set-default EKF2_AID_MASK 35 |
|
param set-default EKF2_IMU_POS_X 0.02 |
|
param set-default EKF2_GPS_POS_X 0.055 |
|
param set-default EKF2_GPS_POS_Z -0.15 |
|
param set-default EKF2_MIN_RNG 0.03 |
|
param set-default EKF2_OF_POS_X 0.055 |
|
param set-default EKF2_OF_POS_Y 0.02 |
|
param set-default EKF2_OF_POS_Z 0.065 |
|
param set-default EKF2_REQ_HDRIFT 0.3 |
|
param set-default EKF2_REQ_SACC 1 |
|
param set-default EKF2_REQ_VDRIFT 0.3 |
|
param set-default EKF2_RNG_A_HMAX 8 |
|
param set-default EKF2_RNG_A_VMAX 2 |
|
param set-default EKF2_RNG_POS_X 0.055 |
|
param set-default EKF2_RNG_POS_Y -0.01 |
|
param set-default EKF2_RNG_POS_Z 0.065 |
|
param set-default EKF2_PCOEF_XP -0.25 |
|
param set-default EKF2_PCOEF_YN -0.55 |
|
param set-default EKF2_PCOEF_YP -0.55 |
|
|
|
# MAVLink parameters |
|
param set-default MAV_0_CONFIG 101 |
|
param set-default MAV_1_CONFIG 102 |
|
param set-default MAV_1_RATE 80000 |
|
param set-default MAV_1_MODE 9 |
|
param set-default SER_TEL1_BAUD 921600 |
|
|
|
# Vehicle attitude PID tuning |
|
param set-default MC_ACRO_EXPO 0 |
|
param set-default MC_ACRO_EXPO_Y 0 |
|
param set-default MC_ACRO_P_MAX 200 |
|
param set-default MC_ACRO_R_MAX 200 |
|
param set-default MC_ACRO_SUPEXPO 0 |
|
param set-default MC_ACRO_SUPEXPOY 0 |
|
param set-default MC_ACRO_Y_MAX 150 |
|
param set-default MC_PITCHRATE_D 0.0015 |
|
param set-default MC_ROLLRATE_D 0.0015 |
|
param set-default MC_YAWRATE_P 0.3 |
|
|
|
# Position Control Tuning |
|
param set-default CP_DIST 6 |
|
param set-default MPC_ACC_DOWN_MAX 5 |
|
param set-default MPC_ACC_HOR_MAX 10 |
|
param set-default MPC_ACC_UP_MAX 4 |
|
param set-default MPC_MANTHR_MIN 0 |
|
param set-default MPC_MAN_Y_MAX 120 |
|
param set-default MPC_TILTMAX_AIR 45 |
|
param set-default MPC_THR_HOVER 0.3 |
|
param set-default MPC_TKO_SPEED 1 |
|
param set-default MPC_VEL_MANUAL 5 |
|
param set-default MPC_XY_CRUISE 5 |
|
param set-default MPC_XY_VEL_MAX 5 |
|
param set-default MPC_XY_VEL_P_ACC 1.58 |
|
param set-default MPC_XY_TRAJ_P 0.3 |
|
param set-default MPC_Z_TRAJ_P 0.3 |
|
param set-default MPC_Z_VEL_P_ACC 5 |
|
param set-default MPC_Z_VEL_I_ACC 3 |
|
param set-default MPC_LAND_ALT1 3 |
|
param set-default MPC_LAND_ALT2 1 |
|
param set-default MPC_POS_MODE 3 |
|
param set-default CP_GO_NO_DATA 1 |
|
|
|
# Navigator Parameters |
|
param set-default NAV_ACC_RAD 2 |
|
|
|
# use oneshot motor output protocol |
|
param set-default PWM_MAIN_RATE 0 |
|
|
|
# RTL Parameters |
|
param set-default RTL_DESCEND_ALT 5 |
|
param set-default RTL_RETURN_ALT 5 |
|
|
|
# Logging Parameters |
|
param set-default SDLOG_PROFILE 131 |
|
|
|
# Sensors Parameters |
|
param set-default SENS_CM8JL65_CFG 104 |
|
param set-default SENS_FLOW_MAXHGT 25 |
|
param set-default SENS_FLOW_MINHGT 0.5 |
|
param set-default SENS_FLOW_ROT 0 |
|
param set-default IMU_GYRO_CUTOFF 100 |
|
param set-default SENS_EN_PMW3901 1 |
|
|
|
# Power Parameters |
|
param set-default BAT1_N_CELLS 4 |
|
param set-default BAT1_A_PER_V 36.364 |
|
param set-default BAT1_V_DIV 18.182 |
|
|
|
# Circuit breakers |
|
param set-default CBRK_IO_SAFETY 22027 |
|
|
|
param set-default THR_MDL_FAC 0.3
|
|
|