Skip to content

Commit

Permalink
gz strivermini initial commit
Browse files Browse the repository at this point in the history
  • Loading branch information
stibipet committed Jun 3, 2024
1 parent 998af28 commit 65f8e74
Show file tree
Hide file tree
Showing 2 changed files with 153 additions and 0 deletions.
149 changes: 149 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4430_gz_ssrc_strivermini
Original file line number Diff line number Diff line change
@@ -0,0 +1,149 @@
#!/bin/sh
#
# @name SSRC Striver Mini
#
# @type Standard VTOL
# @class VTOL
#
# @maintainer
#
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 3
# @output MAIN4 motor 4
# @output AUX1 Aileron 1
# @output AUX2 Aileron 2
# @output AUX3 Elevator 1
# @output AUX4 Elevator 2
# @output AUX5 Rudder
# @output AUX6 Throttle
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
# @board holybro_kakutef7 exclude
#

. ${R}etc/init.d/rc.vtol_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=strivermini}

param set-default SIM_GZ_EN 1

# Control allocator parameters
param set-default CA_AIRFRAME 2
param set-default CA_ROTOR_COUNT 5
param set-default CA_ROTOR0_PX 0.37
param set-default CA_ROTOR0_PY 0.42
param set-default CA_ROTOR1_PX -0.41
param set-default CA_ROTOR1_PY -0.42
param set-default CA_ROTOR2_PX 0.37
param set-default CA_ROTOR2_PY -0.42
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.41
param set-default CA_ROTOR3_PY 0.42
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR4_AX 1.0
param set-default CA_ROTOR4_AZ 0.0
param set-default CA_SV_CS_COUNT 5
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS1_TYPE 2
param set-default CA_SV_CS1_TRQ_R -0.5
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS2_TRQ_P 1.0
param set-default CA_SV_CS3_TYPE 3
param set-default CA_SV_CS3_TRQ_P -1.0
param set-default CA_SV_CS4_TYPE 4
param set-default CA_SV_CS4_TRQ_Y 1.0

# PWM functions
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 201
param set-default PWM_MAIN_FUNC6 202
param set-default PWM_MAIN_FUNC7 203
param set-default PWM_MAIN_FUNC8 204
param set-default PWM_MAIN_FUNC9 205
param set-default PWM_MAIN_FUNC10 105
param set-default PWM_AUX_FUNC1 201
param set-default PWM_AUX_FUNC2 202
param set-default PWM_AUX_FUNC3 203
param set-default PWM_AUX_FUNC4 204
param set-default PWM_AUX_FUNC5 205
param set-default PWM_AUX_FUNC6 105

# Start airspeed sensor driver
ms4525do start -X -f 500

# Airspeed parameters
param set-default ASPD_DO_CHECKS 15
param set-default FW_AIRSPD_MAX 22.0
param set-default FW_AIRSPD_MIN 15.0
param set-default FW_AIRSPD_STALL 12.0
param set-default FW_AIRSPD_TRIM 18.0

# Battery parameters
# Ref: t-drone 22000mah 6s Lion
param set-default BAT1_N_CELLS 6
param set-default BAT1_V_CHARGED 4.1
param set-default BAT1_V_EMPTY 3.2
param set-default BAT1_V_DIV 18.1
param set-default BAT1_SOURCE 0
# Rough guess 50 mOhm
param set-default BAT1_R_INTERNAL 0.0050
param set-default BAT1_CAPACITY 22000

# Ref: t-drone 22000mah 6s Lion
param set-default BAT2_N_CELLS 6
param set-default BAT2_V_CHARGED 4.1
param set-default BAT2_V_EMPTY 3.2
param set-default BAT2_V_DIV 18.1
param set-default BAT2_SOURCE 0
# Rough guess 50 mOhm
param set-default BAT2_R_INTERNAL 0.0050
param set-default BAT2_CAPACITY 22000

# Disable internal magnetometer
param set CAL_MAG0_PRIO 0

# Return mode return altitude
param set-default RTL_RETURN_ALT 30.0

# Fixed wing specific
param set-default FW_MAN_R_MAX 60.0
param set-default FW_RR_IMAX 0.4000
param set-default FW_YR_IMAX 0.4000

# VTOL specific
# VTOL type
param set-default VT_TYPE 2

# Airspeed at which we can start blending both fw and mc controls.
param set-default VT_ARSP_BLEND 10

# Airspeed at which we can switch to fw mode
param set-default VT_ARSP_TRANS 12

# Back-transition duration
param set-default VT_B_TRANS_DUR 4
param set-default VT_B_TRANS_RAMP 3

# Transition duration
param set-default VT_F_TRANS_DUR 6
param set-default VT_F_TRANS_THR 1

# VTOL takeoff
param set-default VTO_LOITER_ALT 20

# QuadChute altitude (transition to quad mode as a failsafe)
param set-default VT_FW_MIN_ALT 5

# QuadChute angle limits
param set-default VT_FW_QC_P 35
param set-default VT_FW_QC_R 60

# Change current sense shunt resistor value
param set-default INA226_SHUNT 0.0005
4 changes: 4 additions & 0 deletions packaging/entrypoint_sitl_gzsim.sh
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,10 @@ case $PX4_VEHICLE_TYPE in
export PX4_SYS_AUTOSTART=4004
export PX4_GZ_MODEL=standard_vtol
;;
strivermini)
export PX4_SYS_AUTOSTART=4430
export PX4_GZ_MODEL=strivermini
;;
fw)
export PX4_SYS_AUTOSTART=4003
export PX4_GZ_MODEL=rc_cessna
Expand Down

0 comments on commit 65f8e74

Please sign in to comment.