mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Support quadtailsitter in SITL
This commit is contained in:
parent
6535cc758e
commit
e3aea937c3
@ -0,0 +1,71 @@
|
||||
#!/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 0.15
|
||||
param set-default CA_ROTOR0_PY 0.23
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.15
|
||||
param set-default CA_ROTOR1_PY -0.23
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.15
|
||||
param set-default CA_ROTOR2_PY -0.23
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.15
|
||||
param set-default CA_ROTOR3_PY 0.23
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
param set-default CA_SV_CS_COUNT 0
|
||||
|
||||
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 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_PITCH_P 5
|
||||
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 7
|
||||
param set-default VT_FW_DIFTHR_S_R 0.5
|
||||
param set-default VT_FW_DIFTHR_S_P 0.5
|
||||
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
|
||||
@ -60,6 +60,7 @@ px4_add_romfs_files(
|
||||
1042_gazebo-classic_tiltrotor
|
||||
1043_gazebo-classic_standard_vtol_drop
|
||||
1044_gazebo-classic_plane_lidar
|
||||
1045_gazebo-classic_quadtailsitter
|
||||
1060_gazebo-classic_rover
|
||||
1061_gazebo-classic_r1_rover
|
||||
1062_flightgear_tf-r1
|
||||
|
||||
@ -91,6 +91,7 @@ if(gazebo_FOUND)
|
||||
plane_catapult
|
||||
plane_lidar
|
||||
px4vision
|
||||
quadtailsitter
|
||||
r1_rover
|
||||
rover
|
||||
standard_vtol
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user