ROMFS defaults drop floating point decimal

This commit is contained in:
Daniel Agar 2018-12-04 17:28:42 -05:00
parent ecbf6ea77b
commit 3a036021ba
52 changed files with 274 additions and 274 deletions

View File

@ -16,10 +16,10 @@ then
# INAV
param set INAV_LIDAR_EST 1
param set INAV_W_XY_FLOW 1.0
param set INAV_W_XY_GPS_P 0.0
param set INAV_W_XY_GPS_V 0.0
param set INAV_W_Z_GPS_P 0.0
param set INAV_W_XY_FLOW 1
param set INAV_W_XY_GPS_P 0
param set INAV_W_XY_GPS_V 0
param set INAV_W_Z_GPS_P 0
# LPE: Flow-only mode
param set LPE_FUSION 242

View File

@ -14,11 +14,11 @@ then
param set EKF2_EV_DELAY 5
# INAV: trust more on the vision input
param set INAV_W_XY_VIS_P 9.0
param set INAV_W_Z_VIS_P 7.0
param set INAV_W_XY_GPS_P 0.0
param set INAV_W_XY_GPS_V 0.0
param set INAV_W_Z_GPS_P 0.0
param set INAV_W_XY_VIS_P 9
param set INAV_W_Z_VIS_P 7
param set INAV_W_XY_GPS_P 0
param set INAV_W_XY_GPS_V 0
param set INAV_W_Z_GPS_P 0
# LPE: Vision + baro
param set LPE_FUSION 132

View File

@ -7,7 +7,7 @@ sh /etc/init.d/rc.fw_defaults
if [ $AUTOCNF = yes ]
then
param set EKF2_ARSP_THR 8.0
param set EKF2_ARSP_THR 8
param set EKF2_FUSE_BETA 1
param set EKF2_MAG_ACCLIM 0
param set EKF2_MAG_YAWLIM 0
@ -31,7 +31,7 @@ then
param set MIS_LTRMIN_ALT 30
param set MIS_TAKEOFF_ALT 30
param set NAV_ACC_RAD 15.0
param set NAV_ACC_RAD 15
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 50

View File

@ -20,16 +20,16 @@ then
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_ACC_HOR_MAX 2
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_TKO_SPEED 1
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_MAX_DN 1.5
param set NAV_ACC_RAD 5.0
param set NAV_ACC_RAD 5
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 5

View File

@ -20,9 +20,9 @@ then
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_ACC_HOR_MAX 2
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_TKO_SPEED 1
param set MPC_XY_P 0.15
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
@ -30,7 +30,7 @@ then
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.8
param set NAV_ACC_RAD 5.0
param set NAV_ACC_RAD 5
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 1.5

View File

@ -20,9 +20,9 @@ then
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_ACC_HOR_MAX 2
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_TKO_SPEED 1
param set MPC_XY_P 0.15
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
@ -30,7 +30,7 @@ then
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.8
param set NAV_ACC_RAD 5.0
param set NAV_ACC_RAD 5
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 1.5

View File

@ -14,7 +14,7 @@ then
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set RTL_DESCEND_ALT 10.0
param set RTL_DESCEND_ALT 10
param set RTL_LAND_DELAY 0
param set TRIG_INTERFACE 3

View File

@ -128,7 +128,7 @@ then
param set MC_ROLLRATE_P 0.2
param set MPC_ALT_MODE 0
param set MPC_HOLD_MAX_Z 2.0
param set MPC_HOLD_MAX_Z 2
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
param set MPC_XY_P 0.8
@ -136,16 +136,16 @@ then
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_D 0.016
param set MPC_JERK_MIN 10.0
param set MPC_JERK_MAX 20.0
param set MPC_ACC_HOR_MAX 3.0
param set MPC_JERK_MIN 10
param set MPC_JERK_MAX 20
param set MPC_ACC_HOR_MAX 3
param set NAV_ACC_RAD 2.0
param set NAV_ACC_RAD 2
param set NAV_DLL_ACT 2
param set RTL_DESCEND_ALT 5.0
param set RTL_DESCEND_ALT 5
param set RTL_LAND_DELAY 5
param set RTL_RETURN_ALT 30.0
param set RTL_RETURN_ALT 30
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0

View File

@ -35,7 +35,7 @@ then
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.28
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
fi
set MIXER quad_w

View File

@ -23,18 +23,18 @@ sh /etc/init.d/rc.mc_defaults
if [ $AUTOCNF = yes ]
then
# TODO tune roll/pitch separately
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.15
param set MC_ROLLRATE_I 0.05
param set MC_ROLLRATE_D 0.004
param set MC_PITCH_P 7.0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.15
param set MC_PITCHRATE_I 0.05
param set MC_PITCHRATE_D 0.004
param set MC_YAW_P 2.5
param set MC_YAWRATE_P 0.25
param set MC_YAWRATE_I 0.25
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set BAT_V_DIV 12.27559
param set BAT_A_PER_V 15.39103

View File

@ -26,18 +26,18 @@ if [ $AUTOCNF = yes ]
then
param set BAT_N_CELLS 4
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.13
param set MC_ROLLRATE_I 0.05
param set MC_ROLLRATE_D 0.004
param set MC_PITCH_P 7.0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.19
param set MC_PITCHRATE_I 0.05
param set MC_PITCHRATE_D 0.004
param set MC_YAW_P 4.0
param set MC_YAW_P 4
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
fi
set MIXER quad_w

View File

@ -27,18 +27,18 @@ then
param set BAT_N_CELLS 6
param set BAT_V_EMPTY 3.5
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.08
param set MC_ROLLRATE_I 0.02
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.02
param set MC_PITCHRATE_D 0.005
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set MPC_XY_VEL_MAX 2

View File

@ -14,7 +14,7 @@ if [ $AUTOCNF = yes ]
then
param set BAT_N_CELLS 3
param set COM_DISARM_LAND 5.0
param set COM_DISARM_LAND 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
@ -36,9 +36,9 @@ then
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_ACC_HOR_MAX 2
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_TKO_SPEED 1
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
@ -47,13 +47,13 @@ then
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 5.0
param set NAV_ACC_RAD 5
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 80
param set RTL_DESCEND_ALT 10.0
param set RTL_DESCEND_ALT 10
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set RTL_RETURN_ALT 30
param set SDLOG_DIRS_MAX 7
param set SYS_MC_EST_GROUP 2

View File

@ -21,26 +21,26 @@ sh /etc/init.d/rc.mc_defaults
if [ $AUTOCNF = yes ]
then
param set MC_PITCH_P 4.0
param set MC_PITCH_P 4
param set MC_PITCHRATE_P 0.24
param set MC_PITCHRATE_I 0.09
param set MC_PITCHRATE_D 0.013
param set MC_PITCHRATE_MAX 180.0
param set MC_PITCHRATE_MAX 180
param set MC_ROLL_P 4.0
param set MC_ROLL_P 4
param set MC_ROLLRATE_P 0.16
param set MC_ROLLRATE_I 0.07
param set MC_ROLLRATE_D 0.009
param set MC_ROLLRATE_MAX 180.0
param set MC_ROLLRATE_MAX 180
param set MC_YAW_P 3.0
param set MC_YAW_P 3
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set MPC_HOLD_MAX_XY 0.25
param set MPC_THR_MIN 0.15
param set MPC_Z_VEL_MAX_DN 2.0
param set MPC_Z_VEL_MAX_DN 2
param set BAT_N_CELLS 4
fi

View File

@ -17,21 +17,21 @@ sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 6.0
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.12
param set MC_ROLLRATE_I 0.002
param set MC_ROLLRATE_D 0.003
param set MC_ROLLRATE_FF 0.0
param set MC_ROLLRATE_FF 0
param set MC_PITCH_P 4.5
param set MC_PITCHRATE_P 0.3
param set MC_PITCHRATE_I 0.002
param set MC_PITCHRATE_D 0.003
param set MC_PITCHRATE_FF 0.0
param set MC_PITCHRATE_FF 0
param set MC_YAW_P 3.8
param set MC_YAWRATE_P 0.22
param set MC_YAWRATE_I 0.02
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_FF 0.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_FF 0
param set VT_IDLE_PWM_MC 1080
param set VT_ELEV_MC_LOCK 0

View File

@ -22,21 +22,21 @@ sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.19
param set MC_ROLLRATE_I 0.002
param set MC_ROLLRATE_D 0.005
param set MC_ROLLRATE_FF 0.0
param set MC_PITCH_P 7.0
param set MC_ROLLRATE_FF 0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.14
param set MC_PITCHRATE_I 0.002
param set MC_PITCHRATE_D 0.004
param set MC_PITCHRATE_FF 0.0
param set MC_YAW_P 4.0
param set MC_PITCHRATE_FF 0
param set MC_YAW_P 4
param set MC_YAWRATE_P 0.22
param set MC_YAWRATE_I 0.02
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_FF 0.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_FF 0
param set PWM_RATE 400

View File

@ -26,21 +26,21 @@ then
param set PWM_RATE 400
param set MC_ROLL_P 6.0
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.17
param set MC_ROLLRATE_I 0.002
param set MC_ROLLRATE_D 0.004
param set MC_ROLLRATE_FF 0.0
param set MC_PITCH_P 6.0
param set MC_ROLLRATE_FF 0
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.19
param set MC_PITCHRATE_I 0.002
param set MC_PITCHRATE_D 0.004
param set MC_PITCHRATE_FF 0.0
param set MC_PITCHRATE_FF 0
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.22
param set MC_YAWRATE_I 0.02
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_FF 0.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_FF 0
param set MC_YAWRATE_MAX 40
param set MC_YAWRAUTO_MAX 40

View File

@ -24,23 +24,23 @@ then
param set MC_ROLLRATE_P 0.15
param set MC_ROLLRATE_I 0.01
param set MC_ROLLRATE_D 0.003
param set MC_ROLLRATE_FF 0.0
param set MC_ROLLRATE_FF 0
param set MC_PITCH_P 6.5
param set MC_PITCHRATE_P 0.15
param set MC_PITCHRATE_I 0.01
param set MC_PITCHRATE_D 0.003
param set MC_PITCHRATE_FF 0.0
param set MC_PITCHRATE_FF 0
param set MC_YAW_P 3.5
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_FF 0.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_FF 0
param set MC_YAWRATE_MAX 50
param set MC_YAWRAUTO_MAX 20
param set MPC_XY_P 0.8
param set MPC_XY_VEL_P 0.1
param set MPC_ACC_HOR_MAX 2.0
param set MPC_ACC_HOR_MAX 2
param set PWM_AUX_DIS3 950
param set PWM_RATE 400

View File

@ -12,21 +12,21 @@ sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.15
param set MC_ROLLRATE_I 0.002
param set MC_ROLLRATE_D 0.003
param set MC_ROLLRATE_FF 0.0
param set MC_PITCH_P 7.0
param set MC_ROLLRATE_FF 0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.12
param set MC_PITCHRATE_I 0.002
param set MC_PITCHRATE_D 0.003
param set MC_PITCHRATE_FF 0.0
param set MC_PITCHRATE_FF 0
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.22
param set MC_YAWRATE_I 0.02
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_FF 0.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_FF 0
param set MC_YAWRATE_MAX 40
param set MC_YAWRAUTO_MAX 40

View File

@ -12,7 +12,7 @@ sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF = yes ]
then
param set FW_THR_CRUISE 65.0
param set FW_THR_CRUISE 65
param set FW_PR_P 0.08
param set FW_PR_FF 0.5
param set FW_RR_P 0.05
@ -20,25 +20,25 @@ then
param set MIS_YAW_TMT 10
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.15
param set MC_ROLLRATE_I 0.1
param set MC_ROLLRATE_D 0.004
param set MC_ROLLRATE_FF 0.0
param set MC_PITCH_P 7.0
param set MC_ROLLRATE_FF 0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.15
param set MC_PITCHRATE_I 0.1
param set MC_PITCHRATE_D 0.004
param set MC_PITCHRATE_FF 0.0
param set MC_PITCHRATE_FF 0
param set MC_YAW_P 3.5
param set MC_YAWRATE_P 0.6
param set MC_YAWRATE_I 0.04
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_FF 0.0
param set MC_YAWRATE_MAX 40.0
param set MC_YAWRAUTO_MAX 40.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_FF 0
param set MC_YAWRATE_MAX 40
param set MC_YAWRAUTO_MAX 40
param set MPC_ACC_HOR_MAX 2.0
param set MPC_ACC_HOR_MAX 2
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_TKO_SPEED 1.5
param set MPC_LAND_SPEED 0.8
@ -48,9 +48,9 @@ then
param set PWM_AUX_REV2 1
param set PWM_RATE 400
param set VT_ARSP_TRANS 15.0
param set VT_ARSP_BLEND 8.0
param set VT_B_TRANS_DUR 4.0
param set VT_ARSP_TRANS 15
param set VT_ARSP_BLEND 8
param set VT_B_TRANS_DUR 4
param set VT_F_TRANS_THR 0.75
param set VT_IDLE_PWM_MC 1080
param set VT_MOT_COUNT 4

View File

@ -12,52 +12,52 @@ sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF = yes ]
then
param set FW_AIRSPD_MAX 22.0
param set FW_AIRSPD_MIN 14.0
param set FW_AIRSPD_TRIM 16.0
param set FW_L1_PERIOD 25.0
param set FW_AIRSPD_MAX 22
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set FW_L1_PERIOD 25
param set FW_PR_P 0.060
param set FW_P_RMAX_NEG 40.0
param set FW_P_RMAX_POS 40.0
param set FW_P_RMAX_NEG 40
param set FW_P_RMAX_POS 40
param set FW_RR_FF 0.4
param set FW_RR_P 0.04
param set FW_R_RMAX 40.0
param set FW_R_RMAX 40
param set MC_PITCHRATE_D 0.004
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_MAX 60.0
param set MC_PITCHRATE_I 0
param set MC_PITCHRATE_MAX 60
param set MC_PITCHRATE_P 0.21
param set MC_PITCH_P 4.0
param set MC_PITCH_P 4
param set MC_ROLLRATE_D 0.004
param set MC_ROLLRATE_I 0.002
param set MC_ROLLRATE_MAX 60.0
param set MC_ROLLRATE_MAX 60
param set MC_ROLLRATE_P 0.24
param set MC_ROLL_P 4.0
param set MC_ROLL_P 4
param set MC_YAWRATE_I 0.02
param set MC_YAWRATE_MAX 40.0
param set MC_YAWRATE_MAX 40
param set MC_YAWRATE_P 0.18
param set MC_YAWRAUTO_MAX 40.0
param set MC_YAWRAUTO_MAX 40
param set MIS_TAKEOFF_ALT 2.5
param set MIS_YAW_TMT 20.0
param set MIS_YAW_TMT 20
param set MPC_ACC_HOR_MAX 1.0
param set MPC_ACC_HOR_MAX 1
param set MPC_HOLD_MAX_XY 0.5
param set MPC_HOLD_MAX_Z 0.5
param set MPC_LAND_SPEED 1.0
param set MPC_LAND_SPEED 1
param set MPC_MANTHR_MIN 0.05
param set MPC_MAN_Y_MAX 120.0
param set MPC_MAN_Y_MAX 120
param set MPC_THR_MIN 0.07
param set MPC_TILTMAX_AIR 35.0
param set MPC_TILTMAX_LND 20.0
param set MPC_TKO_SPEED 1.0
param set MPC_TILTMAX_AIR 35
param set MPC_TILTMAX_LND 20
param set MPC_TKO_SPEED 1
param set MPC_XY_P 0.3
param set MPC_XY_VEL_MAX 3.0
param set MPC_XY_VEL_MAX 3
param set MPC_XY_VEL_P 0.05
param set MPC_Z_P 0.5
param set MPC_Z_VEL_P 0.1
param set NAV_ACC_RAD 3.0
param set NAV_ACC_RAD 3
param set PWM_AUX_REV1 1
param set PWM_AUX_REV2 1
@ -68,13 +68,13 @@ then
param set PWM_RATE 400
param set VT_ARSP_TRANS 15.0
param set VT_B_TRANS_DUR 4.0
param set VT_ARSP_TRANS 15
param set VT_B_TRANS_DUR 4
param set VT_F_TRANS_THR 0.6
param set VT_IDLE_PWM_MC 1180
param set VT_MOT_COUNT 4
param set VT_TRANS_MIN_TM 5.0
param set VT_TRANS_TIMEOUT 30.0
param set VT_TRANS_MIN_TM 5
param set VT_TRANS_TIMEOUT 30
param set VT_TYPE 2
fi

View File

@ -26,13 +26,13 @@ then
param set FW_ARSP_MODE 2
param set FW_L1_PERIOD 17
param set FW_MAN_R_MAX 50.0
param set FW_MAN_R_MAX 50
param set FW_ACRO_X_MAX 270
param set FW_ACRO_Y_MAX 270
param set FW_ACRO_Z_MAX 180
param set FW_PR_FF 0.5
param set FW_PR_P 0.08
param set FW_PSP_OFF 5.0
param set FW_PSP_OFF 5
param set FW_P_LIM_MAX 30
param set FW_P_LIM_MIN -30
param set FW_P_RMAX_NEG 60
@ -44,10 +44,10 @@ then
param set MC_PITCHRATE_D 0.003
param set MC_PITCHRATE_P 0.15
param set MC_PITCH_P 6.0
param set MC_PITCH_P 6
param set MC_ROLLRATE_D 0.003
param set MC_ROLLRATE_P 0.15
param set MC_ROLL_P 6.0
param set MC_ROLL_P 6
param set MC_YAWRATE_MAX 120
param set MC_YAWRATE_P 0.27
param set MC_YAW_P 2.5
@ -55,23 +55,23 @@ then
param set MC_YAWRATE_P 0.3
param set MPC_LAND_SPEED 1.2
param set MPC_TKO_SPEED 2.5
param set MPC_Z_VEL_MAX_UP 3.0
param set MPC_Z_VEL_MAX_UP 3
param set PWM_RATE 400
param set SENS_BOARD_ROT 8
param set VT_B_TRANS_DUR 1.0
param set VT_B_TRANS_DUR 1
param set VT_F_TRANS_DUR 1.2
param set VT_F_TR_OL_TM 4.0
param set VT_F_TR_OL_TM 4
param set VT_FW_DIFTHR_EN 1
param set VT_FW_DIFTHR_SC 0.17
param set VT_FW_MOT_OFFID 3
param set VT_FW_PERM_STAB 0
param set VT_IDLE_PWM_MC 1200
param set VT_MOT_COUNT 3
param set VT_TILT_FW 1.0
param set VT_TILT_MC 0.0
param set VT_TILT_FW 1
param set VT_TILT_MC 0
param set VT_TILT_TRANS 0.45
param set VT_TRANS_MIN_TM 1.2
param set VT_TRANS_P2_DUR 1.3

View File

@ -25,7 +25,7 @@ then
param set BAT_N_CELLS 4
param set BAT_R_INTERNAL 0.0025
param set COM_DISARM_LAND 5.0
param set COM_DISARM_LAND 5
param set CBRK_AIRSPD_CHK 162128
param set CBRK_IO_SAFETY 22027
@ -74,19 +74,19 @@ then
param set MC_ROLLRATE_P 0.16
param set MC_ROLLRATE_I 0.01
param set MC_ROLLRATE_D 0.003
param set MC_ROLLRATE_FF 0.0
param set MC_ROLLRATE_FF 0
param set MC_ROLLRATE_MAX 80
param set MC_PITCH_P 6.5
param set MC_PITCHRATE_P 0.15
param set MC_PITCHRATE_I 0.05
param set MC_PITCHRATE_D 0.003
param set MC_PITCHRATE_FF 0.0
param set MC_PITCHRATE_FF 0
param set MC_PITCHRATE_MAX 80
param set MC_YAW_P 3.5
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_FF 0.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_FF 0
param set MC_YAWRATE_MAX 20
param set MC_YAWRAUTO_MAX 20
param set MC_AIRMODE 1
@ -98,7 +98,7 @@ then
param set MPC_XY_P 0.8
param set MPC_XY_VEL_P 0.1
param set MPC_XY_VEL_MAX 5
param set MPC_ACC_HOR_MAX 2.0
param set MPC_ACC_HOR_MAX 2
param set MPC_LAND_SPEED 1.2
param set MPC_MAN_R_MAX 30
param set MPC_TILTMAX_LND 35

View File

@ -31,10 +31,10 @@ then
param set MC_YAW_P 2
param set MC_YAWRATE_P 0.1
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_FF 0
param set NAV_ACC_RAD 2.0
param set NAV_ACC_RAD 2
param set PWM_AUX_RATE 50
param set PWM_DISARMED 900
@ -42,8 +42,8 @@ then
param set PWM_MAX 1950
param set PWM_RATE 400
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_RETURN_ALT 30
param set RTL_DESCEND_ALT 10
fi
# This is the gimbal pass mixer

View File

@ -25,29 +25,29 @@ set MIXER blade130
if [ $AUTOCNF = yes ]
then
param set ATT_BIAS_MAX 0.0
param set ATT_BIAS_MAX 0
param set CBRK_IO_SAFETY 22027
param set MC_ROLL_P 5.0
param set MC_ROLLRATE_P 0.0
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_D 0.0
param set MC_ROLL_P 5
param set MC_ROLLRATE_P 0
param set MC_ROLLRATE_I 0
param set MC_ROLLRATE_D 0
param set MC_ROLLRATE_FF 0.15
param set MC_PITCH_P 6.5
param set MC_PITCHRATE_P 0.0
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.0
param set MC_PITCHRATE_P 0
param set MC_PITCHRATE_I 0
param set MC_PITCHRATE_D 0
param set MC_PITCHRATE_FF 0.15
param set MC_YAW_P 3.0
param set MC_YAW_P 3
param set MC_YAWRATE_P 0.1
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MC_ROLLRATE_MAX 720.0
param set MC_PITCHRATE_MAX 720.0
param set MC_YAWRATE_MAX 400.0
param set MC_ACRO_R_MAX 360.0
param set MC_ACRO_P_MAX 360.0
param set MC_YAWRATE_I 0
param set MC_YAWRATE_D 0
param set MC_ROLLRATE_MAX 720
param set MC_PITCHRATE_MAX 720
param set MC_YAWRATE_MAX 400
param set MC_ACRO_R_MAX 360
param set MC_ACRO_P_MAX 360
param set MPC_THR_MIN 0.06
param set MPC_MANTHR_MIN 0.06

View File

@ -27,7 +27,7 @@ set VEHICLE_TYPE mc
if [ $AUTOCNF = yes ]
then
param set NAV_ACC_RAD 2.0
param set NAV_ACC_RAD 2
param set PWM_AUX_RATE 400
param set PWM_AUX_DISARMED 900
@ -38,9 +38,9 @@ then
param set PWM_MAX 1950
param set PWM_RATE 400
param set RTL_DESCEND_ALT 10.0
param set RTL_DESCEND_ALT 10
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set RTL_RETURN_ALT 30
fi
set MIXER dodeca_top_cox

View File

@ -45,7 +45,7 @@ then
# Bottom of bay and nominal zero-pitch attitude differ
# the payload bay is pitched up about 7 degrees
param set SENS_BOARD_Y_OFF 7.0
param set SENS_BOARD_Y_OFF 7
fi
set MIXER phantom

View File

@ -27,7 +27,7 @@ then
param set FW_AIRSPD_MAX 27
param set FW_ATT_TC 0.3
param set FW_L1_DAMPING 0.75
param set FW_L1_PERIOD 20.0
param set FW_L1_PERIOD 20
param set FW_PR_FF 0.35
param set FW_PR_IMAX 0.2
param set FW_PR_P 0.05

View File

@ -17,18 +17,18 @@ set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 8.0
param set MC_ROLL_P 8
param set MC_ROLLRATE_P 0.08
param set MC_ROLLRATE_I 0.16
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 8.0
param set MC_PITCH_P 8
param set MC_PITCHRATE_P 0.1
param set MC_PITCHRATE_I 0.2
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.15
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set MC_TPA_BREAK_P 0.7
param set MC_TPA_RATE_P 0.3

View File

@ -15,7 +15,7 @@ set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
param set ATT_BIAS_MAX 0.0
param set ATT_BIAS_MAX 0
param set CBRK_IO_SAFETY 22027
@ -23,18 +23,18 @@ then
param set MC_TPA_RATE_P 0.5
param set MPC_MANTHR_MIN 0.06
param set MC_ROLL_P 6.0
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.14
param set MC_ROLLRATE_I 0.23
param set MC_ROLLRATE_D 0.0025
param set MC_PITCH_P 7.0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.235
param set MC_PITCHRATE_I 0.17
param set MC_PITCHRATE_D 0.004
param set MC_YAW_P 4
param set MC_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set MPC_THR_MIN 0.06
param set PWM_MIN 1075

View File

@ -15,18 +15,18 @@ set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.15
param set MC_ROLLRATE_I 0.05
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.15
param set MC_PITCHRATE_I 0.05
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
# DJI ESCs do not support calibration and need a higher min
param set PWM_MIN 1230

View File

@ -15,18 +15,18 @@ set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.15
param set MC_ROLLRATE_I 0.05
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.15
param set MC_PITCHRATE_I 0.05
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
# DJI ESCs do not support calibration and need a higher min
param set PWM_MIN 1230

View File

@ -15,18 +15,18 @@ set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.16
param set MC_ROLLRATE_I 0.05
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.16
param set MC_PITCHRATE_I 0.05
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
fi
set MIXER quad_x_can

View File

@ -25,16 +25,16 @@ then
# Set all params here, then disable autoconfig
param set MC_ROLL_P 6.5
param set MC_ROLLRATE_P 0.109999999403953552
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_I 0
param set MC_ROLLRATE_D 0.0006
param set MC_PITCH_P 6.5
param set MC_PITCHRATE_P 0.1
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_I 0
param set MC_PITCHRATE_D 0.000799999
param set MC_YAW_P 1.049999
param set MC_YAWRATE_P 0.05
param set MC_YAWRATE_I 0.001
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
fi
set OUTPUT_MODE bebop

View File

@ -22,18 +22,18 @@ set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.1
param set MC_ROLLRATE_I 0.05
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
param set MC_PITCH_P 7
param set MC_PITCHRATE_P 0.1
param set MC_PITCHRATE_I 0.05
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set PWM_MIN 1200
fi

View File

@ -22,8 +22,8 @@ then
param set MC_PITCHRATE_P 0.11
param set MC_ROLLRATE_P 0.11
param set MPC_MANTHR_MIN 0.08
param set MPC_XY_VEL_MAX 3.0
param set MPC_Z_VEL_MAX_DN 2.0
param set MPC_XY_VEL_MAX 3
param set MPC_Z_VEL_MAX_DN 2
# INAV: higher GPS weights for better altitude control
param set INAV_W_Z_BARO 0.3
@ -31,15 +31,15 @@ then
param set INAV_W_Z_GPS_V 0.8
# takeoff, land and RTL settings
param set MIS_TAKEOFF_ALT 4.0
param set COM_DISARM_LAND 1.0
param set MIS_TAKEOFF_ALT 4
param set COM_DISARM_LAND 1
param set RTL_LAND_DELAY 1
param set RTL_DESCEND_ALT 5.0
param set RTL_RETURN_ALT 15.0
param set MPC_TILTMAX_LND 8.0
param set RTL_DESCEND_ALT 5
param set RTL_RETURN_ALT 15
param set MPC_TILTMAX_LND 8
param set MPC_LAND_SPEED 0.4
param set MPC_HOLD_MAX_Z 1.5
param set MPC_TKO_JMPSPD 2.0
param set MPC_TKO_JMPSPD 2
param set MPC_TKO_SPEED 1.5
# setup

View File

@ -19,7 +19,7 @@ then
param set MC_ROLLRATE_P 0.14
param set MC_ROLLRATE_I 0.1
param set MC_ROLLRATE_D 0.004
param set MC_PITCH_P 6.0
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.14
param set MC_PITCHRATE_I 0.09
param set MC_PITCHRATE_D 0.004

View File

@ -23,13 +23,13 @@ then
param set MC_ROLLRATE_P 0.14
param set MC_ROLLRATE_I 0.1
param set MC_ROLLRATE_D 0.004
param set MC_PITCH_P 6.0
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.14
param set MC_PITCHRATE_I 0.09
param set MC_PITCHRATE_D 0.004
param set MC_YAW_P 4
param set NAV_ACC_RAD 2.0
param set NAV_ACC_RAD 2
param set PWM_AUX_DISARMED 950
param set PWM_AUX_RATE 50
@ -37,8 +37,8 @@ then
param set PWM_MAX 1900
param set PWM_RATE 50
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_RETURN_ALT 30
param set RTL_DESCEND_ALT 10
fi
set MIXER quad_h

View File

@ -15,24 +15,24 @@ set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
param set MC_ROLL_P 8.0
param set MC_ROLL_P 8
param set MC_ROLLRATE_P 0.08
param set MC_ROLLRATE_I 0.25
param set MC_ROLLRATE_D 0.001
param set MC_PITCH_P 8.0
param set MC_PITCH_P 8
param set MC_PITCHRATE_P 0.08
param set MC_PITCHRATE_I 0.25
param set MC_PITCHRATE_D 0.001
param set MC_YAW_P 4.0
param set MC_YAW_P 4
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set MC_ROLLRATE_MAX 1600.0
param set MC_PITCHRATE_MAX 1600.0
param set MC_YAWRATE_MAX 1000.0
param set MC_ROLLRATE_MAX 1600
param set MC_PITCHRATE_MAX 1600
param set MC_YAWRATE_MAX 1000
param set MPC_MANTHR_MIN 0.0
param set MPC_MANTHR_MIN 0
param set MPC_MAN_TILT_MAX 60
# use thrust curve factor (instead of TPA)
@ -46,7 +46,7 @@ then
param set SDLOG_PROFILE 19
# disable RC filtering
param set RC_FLT_CUTOFF 0.00000
param set RC_FLT_CUTOFF 0
param set CBRK_IO_SAFETY 22027
fi

View File

@ -28,33 +28,33 @@ set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
param set ATT_BIAS_MAX 0.0
param set ATT_BIAS_MAX 0
param set CBRK_IO_SAFETY 22027
param set MC_ROLL_P 8.0
param set MC_ROLL_P 8
param set MC_ROLLRATE_P 0.19
param set MC_ROLLRATE_I 0.1
param set MC_ROLLRATE_D 0.0055
param set MC_PITCH_P 8.0
param set MC_PITCH_P 8
param set MC_PITCHRATE_P 0.19
param set MC_PITCHRATE_I 0.1
param set MC_PITCHRATE_D 0.0055
param set MC_YAW_P 4.0
param set MC_YAW_P 4
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_ROLLRATE_MAX 720.0
param set MC_PITCHRATE_MAX 720.0
param set MC_YAWRATE_MAX 400.0
param set MC_ACRO_R_MAX 360.0
param set MC_ACRO_P_MAX 360.0
param set MC_YAWRATE_D 0
param set MC_ROLLRATE_MAX 720
param set MC_PITCHRATE_MAX 720
param set MC_YAWRATE_MAX 400
param set MC_ACRO_R_MAX 360
param set MC_ACRO_P_MAX 360
param set MC_TPA_BREAK_D 0.3
param set MC_TPA_BREAK_I 1.0
param set MC_TPA_BREAK_I 1
param set MC_TPA_BREAK_P 0.3
param set MC_TPA_RATE_D 1.0
param set MC_TPA_RATE_I 0.0
param set MC_TPA_RATE_P 1.0
param set MC_TPA_RATE_D 1
param set MC_TPA_RATE_I 0
param set MC_TPA_RATE_P 1
param set MPC_THR_MIN 0.06
param set MPC_MANTHR_MIN 0.06

View File

@ -26,8 +26,8 @@ then
param set MC_PITCHRATE_I 0.05
param set MC_PITCHRATE_D 0.001
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_I 0
param set MC_YAWRATE_D 0
param set PWM_MIN 1200
fi

View File

@ -23,14 +23,14 @@ if [ $AUTOCNF = yes ]
then
# Set all params here, then disable autoconfig
param set COM_DISARM_LAND 3.0
param set COM_DISARM_LAND 3
param set EKF2_GPS_POS_X -0.0600
param set EKF2_GPS_POS_Z -0.1000
param set EKF2_MIN_OBS_DT 50
param set EKF2_BARO_GATE 10.0
param set EKF2_BARO_NOISE 5.0
param set EKF2_BARO_GATE 10
param set EKF2_BARO_NOISE 5
param set EKF2_ACC_NOISE 0.7
param set LNDMC_Z_VEL_MAX 2.0000
@ -45,10 +45,10 @@ then
param set MC_PITCHRATE_I 0.07
param set MC_PITCHRATE_D 0.0012
param set MC_PITCHRATE_MAX 360
param set MC_YAW_P 4.0
param set MC_YAW_P 4
param set MC_YAWRATE_P 0.119999997317790985
param set MC_YAWRATE_I 0.050000000745058060
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set MPC_LAND_SPEED 0.7000
param set MPC_MANTHR_MIN 0.0400

View File

@ -31,14 +31,14 @@ then
param set MC_PITCHRATE_I 0.2
param set MC_PITCHRATE_D 0.0017
param set MC_YAW_P 1.0
param set MC_YAW_P 1
param set MC_YAWRATE_P 0.15
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set MC_ACRO_R_MAX 1000.0
param set MC_ACRO_P_MAX 1000.0
param set MC_ACRO_Y_MAX 1000.0
param set MC_ACRO_R_MAX 1000
param set MC_ACRO_P_MAX 1000
param set MC_ACRO_Y_MAX 1000
param set MC_TPA_BREAK_P 0.5
param set MC_TPA_BREAK_D 0.7

View File

@ -24,18 +24,18 @@ if [ $AUTOCNF = yes ]
then
param set BAT_N_CELLS 1
param set MC_ROLL_P 8.0
param set MC_ROLL_P 8
param set MC_ROLLRATE_P 0.19
param set MC_ROLLRATE_I 0.1
param set MC_ROLLRATE_D 0.0055
param set MC_PITCH_P 8.0
param set MC_PITCH_P 8
param set MC_PITCHRATE_P 0.19
param set MC_PITCHRATE_I 0.1
param set MC_PITCHRATE_D 0.0055
param set MC_YAW_P 4.0
param set MC_YAW_P 4
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_D 0
param set PWM_DISARMED 0
param set PWM_MIN 500

View File

@ -78,7 +78,7 @@ then
param set EKF2_PCOEF_XN 0.1
param set EKF2_PCOEF_XP -0.5
param set EKF2_RNG_AID 1
param set EKF2_RNG_A_VMAX 20.0
param set EKF2_RNG_A_VMAX 20
param set EKF2_RNG_NOISE 0.2
# gps
@ -89,67 +89,67 @@ then
# land detector
param set LNDMC_THR_RANGE 0.50
param set LNDMC_XY_VEL_MAX 1.0
param set LNDMC_ROT_MAX 50.0
param set LNDMC_XY_VEL_MAX 1
param set LNDMC_ROT_MAX 50
# mavlink stream configuration
param set MAV_1_CONFIG 102
param set MAV_1_RATE 20000
# mc_att_control
param set MC_ACRO_P_MAX 360.0
param set MC_ACRO_R_MAX 360.0
param set MC_ACRO_Y_MAX 360.0
param set MC_ACRO_P_MAX 360
param set MC_ACRO_R_MAX 360
param set MC_ACRO_Y_MAX 360
param set MC_ROLL_P 6.0
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.055
param set MC_ROLLRATE_I 0.2
param set MC_ROLLRATE_D 0.0012
param set MC_ROLLRATE_MAX 180.0
param set MC_ROLLRATE_MAX 180
param set MC_PITCHRATE_P 0.06
param set MC_PITCHRATE_I 0.2
param set MC_PITCHRATE_D 0.0012
param set MC_PITCHRATE_MAX 180.0
param set MC_PITCHRATE_MAX 180
param set MC_YAW_P 1.0
param set MC_YAW_P 1
param set MC_YAWRATE_P 0.08
param set MC_YAWRATE_I 0.08
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_MAX 180.0
param set MC_YAWRATE_D 0
param set MC_YAWRATE_MAX 180
param set MOT_SLEW_MAX 0.15
# mc_pos_control
param set MPC_ACC_DOWN_MAX 10.0
param set MPC_ACC_HOR 10.0
param set MPC_ACC_HOR_MAX 15.0
param set MPC_ACC_UP_MAX 10.0
param set MPC_JERK_MAX 5.0
param set MPC_LAND_ALT1 8.0
param set MPC_LAND_ALT2 5.0
param set MPC_ACC_DOWN_MAX 10
param set MPC_ACC_HOR 10
param set MPC_ACC_HOR_MAX 15
param set MPC_ACC_UP_MAX 10
param set MPC_JERK_MAX 5
param set MPC_LAND_ALT1 8
param set MPC_LAND_ALT2 5
param set MPC_MANTHR_MAX 0.85
param set MPC_MANTHR_MIN 0.15
param set MPC_MAN_TILT_MAX 45.0
param set MPC_MAN_Y_MAX 200.0
param set MPC_MAN_TILT_MAX 45
param set MPC_MAN_Y_MAX 200
param set MPC_THR_MAX 0.85
param set MPC_THR_MIN 0.15
param set MPC_TILTMAX_AIR 45.0
param set MPC_TILTMAX_AIR 45
param set MPC_TKO_RAMP_T 0.75
param set MPC_TKO_SPEED 0.75
param set MPC_VEL_MANUAL 26.5
param set MPC_XY_CRUISE 15.0
param set MPC_XY_CRUISE 15
param set MPC_XY_P 1.15
param set MPC_XY_VEL_P 0.14
param set MPC_XY_VEL_I 0.014
param set MPC_XY_VEL_D 0.014
param set MPC_XY_VEL_MAX 26.5
param set MPC_Z_P 0.8
param set MPC_TILTMAX_LND 18.0
param set MPC_TILTMAX_LND 18
param set MPC_Z_VEL_D 0.02
param set MPC_Z_VEL_MAX_DN 2.5
param set MPC_Z_VEL_MAX_UP 6.0
param set MPC_Z_VEL_MAX_UP 6
# navigator
param set NAV_ACC_RAD 2.5

View File

@ -1,6 +1,6 @@
#!nsh
#
# @name Crazyflie 2.0
# @name Crazyflie 2
#
# @board px4_fmu-v2 exclude
# @board px4_fmu-v3 exclude
@ -28,7 +28,7 @@ then
param set CBRK_USB_CHK 197848
param set COM_RC_IN_MODE 1
param set EKF2_ABL_LIM 2.0
param set EKF2_ABL_LIM 2
param set EKF2_AID_MASK 3
param set EKF2_HGT_MODE 2
param set EKF2_MAG_TYPE 1
@ -47,10 +47,10 @@ then
param set MC_ROLLRATE_I 0.2
param set MC_ROLLRATE_P 0.07
param set MC_ROLL_P 6.5
param set MC_YAW_P 3.0
param set MC_YAW_P 3
param set MPC_THR_HOVER 0.7
param set MPC_THR_MAX 1.0
param set MPC_THR_MAX 1
param set MPC_Z_P 1.5
param set MPC_Z_VEL_I 0.3
param set MPC_Z_VEL_P 0.4

View File

@ -19,7 +19,7 @@ then
param set COM_POS_FS_PROB 1
param set COM_VEL_FS_EVH 5
param set EKF2_ARSP_THR 8.0
param set EKF2_ARSP_THR 8
param set EKF2_FUSE_BETA 1
param set EKF2_MAG_ACCLIM 0
param set EKF2_MAG_YAWLIM 0

View File

@ -9,10 +9,10 @@ set VEHICLE_TYPE mc
if [ $AUTOCNF = yes ]
then
param set NAV_ACC_RAD 2.0
param set NAV_ACC_RAD 2
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_RETURN_ALT 30
param set RTL_DESCEND_ALT 10
param set RTL_LAND_DELAY 0
param set PWM_MAX 1950

View File

@ -16,7 +16,7 @@ then
param set MIS_TAKEOFF_ALT 0.01
param set NAV_DLL_ACT 0
param set NAV_ACC_RAD 2.0
param set NAV_ACC_RAD 2
# Temporary.
param set NAV_FW_ALT_RAD 1000

View File

@ -12,10 +12,10 @@ then
param set MIS_TAKEOFF_ALT 20
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2.0
param set MPC_ACC_HOR_MAX 2
param set MPC_LAND_SPEED 0.7
param set MPC_TKO_SPEED 1.0
param set MPC_XY_VEL_MAX 4.0
param set MPC_TKO_SPEED 1
param set MPC_XY_VEL_MAX 4
param set MPC_Z_VEL_MAX_DN 1.5
param set NAV_ACC_RAD 3

View File

@ -1,4 +1,4 @@
Tilt-Quadrotor mixer for PX4FMU (2/2) V2.0
Tilt-Quadrotor mixer for PX4FMU (2/2) V2
===========================
This file defines the aux outputs mixer for a Tilt-quadrotor in the + configuration.

View File

@ -1,4 +1,4 @@
Tilt-Quadrotor mixer for PX4FMU (1/2) V2.0
Tilt-Quadrotor mixer for PX4FMU (1/2) V2
===========================
This file defines the main outputs mixer for a Tilt-quadrotor in the + configuration.