Skip to content

Commit 2ec2a7b

Browse files
committed
Implement gazbo-classic simulation of dual tailsitter
- Update submodule sitl_gazebo-classic. - Modified the 1041_gazebo-classic_tailsitter parameter to achieve stable flight. - Add advanced_tailsitter
1 parent 82e3322 commit 2ec2a7b

File tree

4 files changed

+70
-39
lines changed

4 files changed

+70
-39
lines changed
Lines changed: 15 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -1,77 +1,53 @@
11
#!/bin/sh
22
#
3-
# @name Quadrotor + Tailsitter
3+
# @name Tailsitter
44
#
5-
# @type VTOL Quad Tailsitter
5+
# @type VTOL Tailsitter
66
#
77

88
. ${R}etc/init.d/rc.vtol_defaults
99

10-
param set-default MAV_TYPE 20
10+
param set-default MAV_TYPE 19
1111

1212
param set-default EKF2_FUSE_BETA 0 # side slip fusion is currently not supported for tailsitters
1313

1414
param set-default CA_AIRFRAME 4
1515

16-
param set-default CA_ROTOR_COUNT 4
17-
param set-default CA_ROTOR0_PX 1
18-
param set-default CA_ROTOR0_PY 1
16+
param set-default CA_ROTOR_COUNT 2
1917
param set-default CA_ROTOR0_KM 0.05
20-
param set-default CA_ROTOR1_PX -1
21-
param set-default CA_ROTOR1_PY -1
22-
param set-default CA_ROTOR1_KM 0.05
23-
param set-default CA_ROTOR2_PX 1
24-
param set-default CA_ROTOR2_PY -1
25-
param set-default CA_ROTOR2_KM -0.05
26-
param set-default CA_ROTOR3_PX -1
27-
param set-default CA_ROTOR3_PY 1
28-
param set-default CA_ROTOR3_KM -0.05
18+
param set-default CA_ROTOR0_PY -0.3
19+
param set-default CA_ROTOR0_PZ -0.2
20+
param set-default CA_ROTOR1_KM -0.05
21+
param set-default CA_ROTOR1_PY 0.3
22+
param set-default CA_ROTOR1_PZ -0.2
2923

3024
param set-default CA_SV_CS_COUNT 2
3125
param set-default CA_SV_CS0_TYPE 5
3226
param set-default CA_SV_CS0_TRQ_P 0.5
33-
param set-default CA_SV_CS0_TRQ_Y -0.5
27+
param set-default CA_SV_CS0_TRQ_Y 0.5
3428
param set-default CA_SV_CS1_TYPE 6
3529
param set-default CA_SV_CS1_TRQ_P 0.5
36-
param set-default CA_SV_CS1_TRQ_Y 0.5
30+
param set-default CA_SV_CS1_TRQ_Y -0.5
31+
param set-default VT_ELEV_MC_LOCK 0
3732

3833
param set-default PWM_MAIN_FUNC1 101
3934
param set-default PWM_MAIN_FUNC2 102
40-
param set-default PWM_MAIN_FUNC3 103
41-
param set-default PWM_MAIN_FUNC4 104
42-
param set-default PWM_MAIN_FUNC5 0
43-
param set-default PWM_MAIN_FUNC6 201
44-
param set-default PWM_MAIN_FUNC7 202
45-
param set-default PWM_MAIN_REV 96 # invert both elevons
35+
param set-default PWM_MAIN_FUNC3 201
36+
param set-default PWM_MAIN_FUNC4 202
4637

4738
# Single-EKF (for replay)
4839
param set-default EKF2_MULTI_IMU 0
4940
param set-default SENS_IMU_MODE 1
5041

51-
param set-default FW_P_TC 0.6
52-
5342
param set-default FW_PR_FF 0.0
5443
param set-default FW_PSP_OFF 2
55-
param set-default FW_RR_FF 0.1
56-
param set-default FW_RR_I 0.2
57-
param set-default FW_RR_P 0.5
58-
param set-default FW_THR_TRIM 0.35
59-
param set-default FW_THR_MAX 0.8
60-
param set-default FW_THR_MIN 0.05
61-
param set-default FW_T_CLMB_MAX 6
62-
param set-default FW_T_HRATE_FF 0.5
63-
param set-default FW_T_SINK_MAX 3
64-
param set-default FW_T_SINK_MIN 1.6
65-
6644
param set-default MC_AIRMODE 1
67-
param set-default MC_ROLL_P 3
68-
param set-default MC_PITCH_P 3
45+
param set-default FW_THR_TRIM 0.6
6946

7047
param set-default VT_ARSP_TRANS 10
7148
param set-default VT_B_TRANS_DUR 5
7249
param set-default VT_FW_DIFTHR_EN 1
7350
param set-default VT_FW_DIFTHR_S_Y 1
74-
param set-default VT_F_TRANS_DUR 1.5
7551
param set-default VT_TYPE 0
7652

7753
param set-default WV_EN 0
Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
#!/bin/sh
2+
#
3+
# @name Advanced Tailsitter SITL
4+
#
5+
# @type VTOL Tailsitter
6+
#
7+
8+
. ${R}etc/init.d/rc.vtol_defaults
9+
10+
param set-default MAV_TYPE 19
11+
12+
param set-default EKF2_FUSE_BETA 0 # side slip fusion is currently not supported for tailsitters
13+
14+
param set-default CA_AIRFRAME 4
15+
16+
param set-default CA_ROTOR_COUNT 2
17+
param set-default CA_ROTOR0_KM 0.05
18+
param set-default CA_ROTOR0_PY -0.3
19+
param set-default CA_ROTOR0_PZ -0.2
20+
param set-default CA_ROTOR1_KM -0.05
21+
param set-default CA_ROTOR1_PY 0.3
22+
param set-default CA_ROTOR1_PZ -0.2
23+
24+
param set-default CA_SV_CS_COUNT 2
25+
param set-default CA_SV_CS0_TYPE 5
26+
param set-default CA_SV_CS0_TRQ_P 0.5
27+
param set-default CA_SV_CS0_TRQ_Y 0.5
28+
param set-default CA_SV_CS1_TYPE 6
29+
param set-default CA_SV_CS1_TRQ_P 0.5
30+
param set-default CA_SV_CS1_TRQ_Y -0.5
31+
param set-default VT_ELEV_MC_LOCK 0
32+
33+
param set-default PWM_MAIN_FUNC1 101
34+
param set-default PWM_MAIN_FUNC2 102
35+
param set-default PWM_MAIN_FUNC3 201
36+
param set-default PWM_MAIN_FUNC4 202
37+
38+
# Single-EKF (for replay)
39+
param set-default EKF2_MULTI_IMU 0
40+
param set-default SENS_IMU_MODE 1
41+
42+
param set-default FW_PR_FF 0
43+
param set-default FW_PSP_OFF 2
44+
param set-default MC_AIRMODE 1
45+
param set-default FW_THR_TRIM 0.6
46+
47+
param set-default VT_ARSP_TRANS 10
48+
param set-default VT_B_TRANS_DUR 5
49+
param set-default VT_FW_DIFTHR_EN 1
50+
param set-default VT_FW_DIFTHR_S_Y 1
51+
param set-default VT_TYPE 0
52+
53+
param set-default WV_EN 0

ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,7 @@ px4_add_romfs_files(
6262
1043_gazebo-classic_standard_vtol_drop
6363
1044_gazebo-classic_plane_lidar
6464
1045_gazebo-classic_quadtailsitter
65+
1046_gazebo-classic_advanced_tailsitter
6566
1062_flightgear_tf-r1
6667
1070_gazebo-classic_boat
6768

src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,7 @@ if(gazebo_FOUND)
7979
)
8080

8181
set(models
82+
advanced_tailsitter
8283
advanced_plane
8384
believer
8485
boat

0 commit comments

Comments
 (0)