diff --git a/ROMFS/px4fmu_common/init.d/2200_standard_vtol_hitl b/ROMFS/px4fmu_common/init.d/2200_standard_vtol_hitl new file mode 100644 index 0000000000..ee1a1b04d5 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/2200_standard_vtol_hitl @@ -0,0 +1,79 @@ +#!nsh +# +# @name Standard vtol HITL +# +# @type Standard VTOL +# @class VTOL +# +# @maintainer Roman Bapst +# + +sh /etc/init.d/rc.vtol_defaults + +if [ $AUTOCNF == yes ] +then + param set BAT_N_CELLS 3 + param set CAL_ACC0_ID 1376264 + param set CAL_ACC0_XOFF 0.01 + param set CAL_ACC0_XSCALE 1.01 + param set CAL_ACC0_YOFF -0.01 + param set CAL_ACC0_YSCALE 1.01 + param set CAL_ACC0_ZOFF 0.01 + param set CAL_ACC0_ZSCALE 1.01 + param set CAL_ACC1_ID 1310728 + param set CAL_ACC1_XOFF 0.01 + param set CAL_GYRO0_ID 2293768 + param set CAL_GYRO0_XOFF 0.01 + param set CAL_MAG0_ID 196616 + param set CAL_MAG0_XOFF 0.01 + param set COM_DISARM_LAND 5 + param set COM_RC_IN_MODE 1 + param set EKF2_AID_MASK 1 + param set EKF2_ANGERR_INIT 0.01 + param set EKF2_GBIAS_INIT 0.01 + param set EKF2_HGT_MODE 0 + param set EKF2_MAG_TYPE 1 + param set FW_AIRSPD_MAX 25 + param set FW_AIRSPD_MIN 14 + param set FW_AIRSPD_TRIM 16 + param set MAV_TYPE 20 + param set MC_PITCH_P 6 + param set MC_PITCHRATE_P 0.2 + param set MC_ROLL_P 6 + param set MC_ROLLRATE_P 0.3 + param set MIS_LTRMIN_ALT 10 + param set MIS_TAKEOFF_ALT 10 + param set MIS_YAW_TMT 10 + param set MPC_ACC_HOR_MAX 2 + param set MPC_ACC_HOR_MAX 2.0 + param set MPC_THR_MIN 0.1 + param set MPC_TKO_SPEED 1.0 + 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_I 0.15 + 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_DLL_ACT 2 + param set NAV_LOITER_RAD 80 + param set RTL_DESCEND_ALT 10.0 + param set RTL_LAND_DELAY 0 + param set RTL_RETURN_ALT 30.0 + param set SDLOG_DIRS_MAX 7 + param set SENS_BOARD_ROT 0 + param set SENS_BOARD_X_OFF 0.000001 + param set SENS_DPRES_OFF 0.001 + param set SYS_MC_EST_GROUP 2 + param set SYS_RESTART_TYPE 2 + param set VT_F_TRANS_THR 0.75 + param set VT_MOT_COUNT 4 + param set VT_TYPE 2 +fi + +set MIXER standard_vtol_hitl + +set PWM_OUT 1234 + +param set SYS_HITL 1 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/mixers/standard_vtol_hitl.main.mix b/ROMFS/px4fmu_common/mixers/standard_vtol_hitl.main.mix new file mode 100644 index 0000000000..6e84c2814b --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/standard_vtol_hitl.main.mix @@ -0,0 +1,26 @@ +Mixer for standard vtol plane (SITL) with motor x configuration +========================================================= + +This file defines a single mixer for a standard vtol plane (SITL gazebo) with motors in X configuration. The plane has two ailerons and one elevator. + +R: 4x 10000 10000 10000 0 + +# mixer for the pusher/puller throttle +M: 1 +O: 10000 10000 0 -10000 10000 +S: 1 3 0 20000 -10000 -10000 10000 + +# mixer for the left aileron +M: 1 +O: 10000 10000 0 -10000 10000 +S: 1 0 10000 10000 0 -10000 10000 + +# mixer for the right aileron +M: 1 +O: 10000 10000 0 -10000 10000 +S: 1 0 -10000 -10000 0 -10000 10000 + +# mixer for the elevator +M: 1 +O: 10000 10000 0 -10000 10000 +S: 1 1 10000 10000 0 -10000 10000