|
| 1 | +#!/bin/sh |
| 2 | +# |
| 3 | +# @name Advanced Technology Labs (ATL) Mantis EDU |
| 4 | +# |
| 5 | +# @type Quadrotor x |
| 6 | +# @class Copter |
| 7 | +# |
| 8 | +# @output MAIN1 motor 1 |
| 9 | +# @output MAIN2 motor 2 |
| 10 | +# @output MAIN3 motor 3 |
| 11 | +# @output MAIN4 motor 4 |
| 12 | +# |
| 13 | +# @maintainer |
| 14 | +# @board px4_fmu-v2 exclude |
| 15 | +# |
| 16 | + |
| 17 | +. ${R}etc/init.d/rc.mc_defaults |
| 18 | + |
| 19 | +set MIXER none |
| 20 | +set MIXER_AUX none |
| 21 | + |
| 22 | + |
| 23 | +# Battery settings |
| 24 | +param set-default BAT_CRIT_THR 0.20 |
| 25 | +param set-default BAT_EMERGEN_THR 0.05 |
| 26 | +param set-default BAT_LOW_THR 0.25 |
| 27 | + |
| 28 | +param set-default BAT1_CAPACITY 2800.0 |
| 29 | +param set-default BAT1_N_CELLS 3 |
| 30 | +param set-default BAT1_R_INTERNAL 0.02 |
| 31 | +param set-default BAT1_V_CHARGED 4.26 |
| 32 | +param set-default BAT1_V_EMPTY 3.45 |
| 33 | + |
| 34 | +param set-default CBRK_SUPPLY_CHK 894281 |
| 35 | + |
| 36 | +param set-default COM_DISARM_LAND 0.1 |
| 37 | +param set-default COM_DISARM_PRFLT 3 |
| 38 | +param set-default COM_DL_LOSS_T 10 |
| 39 | +param set-default COM_FLTMODE1 -1 |
| 40 | +param set-default COM_FLTMODE2 -1 |
| 41 | +param set-default COM_FLTMODE3 -1 |
| 42 | +param set-default COM_FLTMODE4 2 |
| 43 | +param set-default COM_FLTMODE5 -1 |
| 44 | +param set-default COM_FLTMODE6 6 |
| 45 | +param set-default COM_RC_LOSS_T 3 |
| 46 | +param set-default COM_RC_OVERRIDE 1 |
| 47 | + |
| 48 | + |
| 49 | +# ekf2 |
| 50 | +param set-default EKF2_AID_MASK 35 |
| 51 | +param set-default EKF2_BARO_DELAY 0 |
| 52 | +param set-default EKF2_BARO_NOISE 2.0 |
| 53 | + |
| 54 | +param set-default EKF2_BCOEF_X 31.5 |
| 55 | +param set-default EKF2_BCOEF_Y 25.5 |
| 56 | + |
| 57 | +param set-default EKF2_GPS_DELAY 100 |
| 58 | +param set-default EKF2_GPS_POS_X 0.06 |
| 59 | +param set-default EKF2_GPS_POS_Y 0.0 |
| 60 | +param set-default EKF2_GPS_POS_Z 0.0 |
| 61 | +param set-default EKF2_GPS_V_NOISE 0.5 |
| 62 | + |
| 63 | +param set-default EKF2_IMU_POS_X 0.06 |
| 64 | +param set-default EKF2_IMU_POS_Y 0.0 |
| 65 | +param set-default EKF2_IMU_POS_Z 0.0 |
| 66 | + |
| 67 | +param set-default EKF2_MAG_DELAY 0 |
| 68 | +param set-default EKF2_MAG_NOISE 0.1 |
| 69 | + |
| 70 | +param set-default EKF2_MIN_RNG 0.15 |
| 71 | + |
| 72 | +param set-default EKF2_OF_DELAY 38 |
| 73 | +param set-default EKF2_OF_GATE 2.0 |
| 74 | +param set-default EKF2_OF_POS_X -0.035 |
| 75 | +param set-default EKF2_OF_POS_Y 0.0 |
| 76 | +param set-default EKF2_OF_POS_Z 0.033 |
| 77 | + |
| 78 | +param set-default EKF2_PCOEF_XN -0.3 |
| 79 | +param set-default EKF2_PCOEF_XP -0.4 |
| 80 | +param set-default EKF2_PCOEF_YN -0.4 |
| 81 | +param set-default EKF2_PCOEF_YP -0.4 |
| 82 | +param set-default EKF2_PCOEF_Z 0.0 |
| 83 | + |
| 84 | +param set-default EKF2_RNG_A_VMAX 1.0 |
| 85 | +param set-default EKF2_RNG_AID 0 |
| 86 | +param set-default EKF2_RNG_DELAY 55 |
| 87 | +param set-default EKF2_RNG_POS_X -0.035 |
| 88 | +param set-default EKF2_RNG_POS_Y 0.0 |
| 89 | +param set-default EKF2_RNG_POS_Z 0.033 |
| 90 | + |
| 91 | +param set-default EKF2_TERR_NOISE 1.0 |
| 92 | + |
| 93 | + |
| 94 | +# Maximum allowed angle velocity in the landed state |
| 95 | +param set-default LNDMC_ROT_MAX 40.0 |
| 96 | + |
| 97 | +# Maximum vertical velocity allowed in the landed state |
| 98 | +param set-default LNDMC_Z_VEL_MAX 0.7 |
| 99 | + |
| 100 | + |
| 101 | +# filtering |
| 102 | +param set-default IMU_DGYRO_CUTOFF 50 |
| 103 | +param set-default IMU_GYRO_CUTOFF 65 |
| 104 | + |
| 105 | + |
| 106 | +# Pitch angle & rate setting |
| 107 | +param set-default MC_PITCHRATE_P 0.075 |
| 108 | +param set-default MC_PITCHRATE_I 0.1 |
| 109 | +param set-default MC_PITCHRATE_D 0.0005 |
| 110 | +param set-default MC_PITCHRATE_MAX 360.0 |
| 111 | +param set-default MC_PITCH_P 8.0 |
| 112 | + |
| 113 | +# Roll angle & rate setting |
| 114 | +param set-default MC_ROLLRATE_P 0.055 |
| 115 | +param set-default MC_ROLLRATE_I 0.1 |
| 116 | +param set-default MC_ROLLRATE_D 0.0005 |
| 117 | +param set-default MC_ROLLRATE_MAX 360.0 |
| 118 | +param set-default MC_ROLL_P 8.0 |
| 119 | + |
| 120 | +# Yaw angle & rate setting |
| 121 | +param set-default MC_YAWRATE_P 0.1 |
| 122 | +param set-default MC_YAWRATE_I 0.1 |
| 123 | +param set-default MC_YAWRATE_MAX 120.0 |
| 124 | +param set-default MC_YAW_P 2.5 |
| 125 | + |
| 126 | +param set-default MPC_ACC_DOWN_MAX 2.0 |
| 127 | +param set-default MPC_ACC_HOR 3.0 |
| 128 | +param set-default MPC_ACC_HOR_MAX 10.0 |
| 129 | +param set-default MPC_ACC_UP_MAX 3.0 |
| 130 | +param set-default MPC_ALT_MODE 0 |
| 131 | +param set-default MPC_LAND_SPEED 0.5 |
| 132 | +param set-default MPC_LAND_VEL_XY 10 |
| 133 | +param set-default MPC_MAN_TILT_MAX 20 |
| 134 | +param set-default MPC_YAWRAUTO_MAX 80.0 |
| 135 | +param set-default MPC_POS_MODE 4 |
| 136 | +param set-default MPC_THR_HOVER 0.54 |
| 137 | +param set-default MPC_THR_MAX 0.9 |
| 138 | +param set-default MPC_THR_MIN 0.06 |
| 139 | +param set-default MPC_TILTMAX_AIR 30 |
| 140 | +param set-default MPC_XY_P 1.0 |
| 141 | +param set-default MPC_XY_VEL_D 0.005 |
| 142 | +param set-default MPC_XY_VEL_I 0.02 |
| 143 | +param set-default MPC_XY_VEL_P 0.15 |
| 144 | +param set-default MPC_Z_P 2.0 |
| 145 | +param set-default MPC_Z_VEL_D 0.0 |
| 146 | +param set-default MPC_Z_VEL_I 0.02 |
| 147 | +param set-default MPC_Z_VEL_MAX_DN 2.0 |
| 148 | +param set-default MPC_Z_VEL_MAX_UP 3.0 |
| 149 | +param set-default MPC_Z_VEL_P 0.27 |
| 150 | + |
| 151 | + |
| 152 | +# gimbal configuration |
| 153 | +param set-default MNT_MODE_IN 1 |
| 154 | +param set-default MNT_MODE_OUT 2 |
| 155 | +param set-default MNT_MAN_PITCH 1 |
| 156 | + |
| 157 | + |
| 158 | +# RC |
| 159 | +param set-default RC_CHAN_CNT 12 |
| 160 | + |
| 161 | +param set-default RC_MAP_THROTTLE 1 |
| 162 | +param set-default RC_MAP_ROLL 2 |
| 163 | +param set-default RC_MAP_PITCH 3 |
| 164 | +param set-default RC_MAP_YAW 4 |
| 165 | +param set-default RC_MAP_FLTMODE 5 |
| 166 | +param set-default RC_MAP_AUX1 7 |
| 167 | + |
| 168 | +param set-default RC1_DZ 10 |
| 169 | +param set-default RC1_MAX 3413 |
| 170 | +param set-default RC1_MIN 683 |
| 171 | +param set-default RC1_REV 1 |
| 172 | +param set-default RC1_TRIM 683 |
| 173 | +param set-default RC2_DZ 10 |
| 174 | +param set-default RC2_MAX 3413 |
| 175 | +param set-default RC2_MIN 683 |
| 176 | +param set-default RC2_REV -1 |
| 177 | +param set-default RC2_TRIM 2048 |
| 178 | +param set-default RC3_DZ 10 |
| 179 | +param set-default RC3_MAX 3413 |
| 180 | +param set-default RC3_MIN 683 |
| 181 | +param set-default RC3_REV 1 |
| 182 | +param set-default RC3_TRIM 2048 |
| 183 | +param set-default RC4_DZ 10 |
| 184 | +param set-default RC4_MAX 3413 |
| 185 | +param set-default RC4_MIN 683 |
| 186 | +param set-default RC4_REV -1 |
| 187 | +param set-default RC4_TRIM 2048 |
| 188 | +param set-default RC5_DZ 10 |
| 189 | +param set-default RC5_MAX 3414 |
| 190 | +param set-default RC5_MIN 2048 |
| 191 | +param set-default RC5_REV 1 |
| 192 | +param set-default RC5_TRIM 2048 |
| 193 | +param set-default RC7_DZ 10 |
| 194 | +param set-default RC7_MAX 3413 |
| 195 | +param set-default RC7_MIN 683 |
| 196 | +param set-default RC7_REV 1 |
| 197 | +param set-default RC7_TRIM 2048 |
0 commit comments