PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter
Daniel Agar 6991ac014c
rename 'gazebo' simulation to 'gazebo-classic' (#20936)
- use `gazebo-classic` everywhere consistently referring to the original Gazebo (eg version 9,10,11)
   - additional `gazebo_*` helper targets added for compatibility, but warn about deprecation and tell you the new target naming
 - use `gz` everywhere when referring to Gazebo (aka Ignition Gazebo or new Gazebo)
2023-01-15 11:36:12 -05:00

80 lines
2.1 KiB
Bash

#!/bin/sh
#
# @name Quadrotor + Tailsitter
#
# @type VTOL Quad Tailsitter
#
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 20
param set-default CA_AIRFRAME 4
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 1
param set-default CA_ROTOR0_PY 2
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -1
param set-default CA_ROTOR1_PY -1
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 1
param set-default CA_ROTOR2_PY -1
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -1
param set-default CA_ROTOR3_PY 1
param set-default CA_ROTOR3_KM -0.05
param set-default CA_SV_CS_COUNT 2
param set-default CA_SV_CS0_TYPE 5
param set-default CA_SV_CS0_TRQ_P 0.5
param set-default CA_SV_CS0_TRQ_Y -0.5
param set-default CA_SV_CS1_TYPE 6
param set-default CA_SV_CS1_TRQ_P 0.5
param set-default CA_SV_CS1_TRQ_Y 0.5
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 0
param set-default PWM_MAIN_FUNC6 201
param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_REV 96 # invert both elevons
param set-default FW_L1_PERIOD 12
param set-default FW_PR_I 0.2
param set-default FW_PR_P 0.2
param set-default FW_PSP_OFF 2
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_P 0.2
param set-default FW_THR_TRIM 0.33
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_T_ALT_TC 2
param set-default FW_T_CLMB_MAX 8
param set-default FW_T_HRATE_FF 0.5
param set-default FW_T_SINK_MAX 2.7
param set-default FW_T_SINK_MIN 2.2
param set-default FW_T_TAS_TC 2
param set-default MC_AIRMODE 1
param set-default MC_ROLLRATE_P 0.3
param set-default MPC_ACC_HOR_MAX 2
param set-default MPC_XY_P 0.8
param set-default MPC_XY_VEL_P_ACC 3
param set-default MPC_XY_VEL_I_ACC 4
param set-default MPC_XY_VEL_D_ACC 0.1
param set-default NAV_ACC_RAD 5
param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_S_Y 0.5
param set-default VT_F_TRANS_DUR 1.5
param set-default VT_F_TRANS_THR 0.7
param set-default VT_TYPE 0
param set-default WV_EN 0