Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,77 +1,53 @@
#!/bin/sh
#
# @name Quadrotor + Tailsitter
# @name Tailsitter
#
# @type VTOL Quad Tailsitter
# @type VTOL Tailsitter
#

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

param set-default MAV_TYPE 20
param set-default MAV_TYPE 19

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

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 1
param set-default CA_ROTOR_COUNT 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_ROTOR0_PY -0.3
param set-default CA_ROTOR0_PZ -0.2
param set-default CA_ROTOR1_KM -0.05
param set-default CA_ROTOR1_PY 0.3
param set-default CA_ROTOR1_PZ -0.2

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_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 CA_SV_CS1_TRQ_Y -0.5
param set-default VT_ELEV_MC_LOCK 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 PWM_MAIN_FUNC6 201
param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_REV 96 # invert both elevons
param set-default PWM_MAIN_FUNC3 201
param set-default PWM_MAIN_FUNC4 202

# Single-EKF (for replay)
param set-default EKF2_MULTI_IMU 0
param set-default SENS_IMU_MODE 1

param set-default FW_P_TC 0.6

param set-default FW_PR_FF 0.0
param set-default FW_PSP_OFF 2
param set-default FW_RR_FF 0.1
param set-default FW_RR_I 0.2
param set-default FW_RR_P 0.5
param set-default FW_THR_TRIM 0.35
param set-default FW_THR_MAX 0.8
param set-default FW_THR_MIN 0.05
param set-default FW_T_CLMB_MAX 6
param set-default FW_T_HRATE_FF 0.5
param set-default FW_T_SINK_MAX 3
param set-default FW_T_SINK_MIN 1.6

param set-default MC_AIRMODE 1
param set-default MC_ROLL_P 3
param set-default MC_PITCH_P 3
param set-default FW_THR_TRIM 0.6

param set-default VT_ARSP_TRANS 10
param set-default VT_B_TRANS_DUR 5
param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_S_Y 1
param set-default VT_F_TRANS_DUR 1.5
param set-default VT_TYPE 0

param set-default WV_EN 0
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
#!/bin/sh
#
# @name Advanced Tailsitter SITL
#
# @type VTOL Tailsitter
#

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

param set-default MAV_TYPE 19

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

param set-default CA_AIRFRAME 4

param set-default CA_ROTOR_COUNT 2
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR0_PY -0.3
param set-default CA_ROTOR0_PZ -0.2
param set-default CA_ROTOR1_KM -0.05
param set-default CA_ROTOR1_PY 0.3
param set-default CA_ROTOR1_PZ -0.2

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 VT_ELEV_MC_LOCK 0

param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 201
param set-default PWM_MAIN_FUNC4 202

# Single-EKF (for replay)
param set-default EKF2_MULTI_IMU 0
param set-default SENS_IMU_MODE 1

param set-default FW_PR_FF 0
param set-default FW_PSP_OFF 2
param set-default MC_AIRMODE 1
param set-default FW_THR_TRIM 0.6

param set-default VT_ARSP_TRANS 10
param set-default VT_B_TRANS_DUR 5
param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_S_Y 1
param set-default VT_TYPE 0

param set-default WV_EN 0
1 change: 1 addition & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ px4_add_romfs_files(
1043_gazebo-classic_standard_vtol_drop
1044_gazebo-classic_plane_lidar
1045_gazebo-classic_quadtailsitter
1046_gazebo-classic_advanced_tailsitter
1062_flightgear_tf-r1
1070_gazebo-classic_boat

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ if(gazebo_FOUND)
)

set(models
advanced_tailsitter
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Given that the tailsitter was not flying in gazebo classic, could we just use that airframe?

the word advanced is associated with the advanced_lift_drag plugin, which is not being used for this tailsitter.

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, thank you for the reminder, it is still waiting for review. @hamishwillee

@mengchaoheng It might still be waiting on your response to this

advanced_plane
believer
boat
Expand Down
Loading