Skip to content

Commit

Permalink
sitl: add support for gz sim with ssrc models and px4 sitl build/launch
Browse files Browse the repository at this point in the history
  • Loading branch information
haitomatic committed Oct 20, 2023
1 parent b385113 commit 782e756
Show file tree
Hide file tree
Showing 9 changed files with 514 additions and 29 deletions.
70 changes: 70 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4401_gz_ssrc_fog_x
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
#!/bin/sh
#
# @name Gazebo x500
#
# @type Quadrotor x
#

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

PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=holybro-x500}

param set-default SIM_GZ_EN 1

param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1

param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4

param set-default CA_ROTOR0_PX 0.175
param set-default CA_ROTOR0_PY 0.175
param set-default CA_ROTOR0_KM 0.05

param set-default CA_ROTOR1_PX -0.175
param set-default CA_ROTOR1_PY -0.175
param set-default CA_ROTOR1_KM 0.05

param set-default CA_ROTOR2_PX 0.175
param set-default CA_ROTOR2_PY -0.175
param set-default CA_ROTOR2_KM -0.05

param set-default CA_ROTOR3_PX -0.175
param set-default CA_ROTOR3_PY 0.175
param set-default CA_ROTOR3_KM -0.05

param set-default SIM_GZ_FUNC1 101
param set-default SIM_GZ_FUNC2 102
param set-default SIM_GZ_FUNC3 103
param set-default SIM_GZ_FUNC4 104

param set-default SIM_GZ_MIN1 150
param set-default SIM_GZ_MIN2 150
param set-default SIM_GZ_MIN3 150
param set-default SIM_GZ_MIN4 150

param set-default SIM_GZ_MAX1 1000
param set-default SIM_GZ_MAX2 1000
param set-default SIM_GZ_MAX3 1000
param set-default SIM_GZ_MAX4 1000

param set-default MPC_THR_HOVER 0.60

# extra
param set COM_RCL_EXCEPT 4
param set NAV_DLL_ACT 0
param set NAV_RCL_ACT 0
param set MAV_0_BROADCAST 1
param set IMU_GYRO_CUTOFF 60
param set IMU_DGYRO_CUTOFF 30
param set MC_ROLLRATE_P 0.14
param set MC_PITCHRATE_P 0.14
param set MC_ROLLRATE_I 0.3
param set MC_PITCHRATE_I 0.3
param set MC_ROLLRATE_D 0.004
param set MC_PITCHRATE_D 0.004
param set BAT_N_CELLS 4
param set SDLOG_MODE 0
109 changes: 109 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4430_gz_ssrc_striver_mini
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
#!/bin/sh
#
# @name Striver mini VTOL
#
# @type Standard VTOL
# @class VTOL
#

. ${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:=striver_mini}

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_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
param set-default BAT1_N_CELLS 4
param set-default BAT1_V_CHARGED 4.2
param set-default BAT1_V_EMPTY 3.6
param set-default BAT1_V_DIV 18.1

# 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
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
#!/bin/sh
#
# @name SSRC Skywalker X8
#
# @type Flying Wing
# @class Plane
#

. /etc/init.d/rc.fw_defaults

PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=skywalker_x8}

param set-default SIM_GZ_EN 1

# Control allocator parameters
param set-default CA_AIRFRAME 1
param set-default CA_ROTOR_COUNT 1
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_R -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_R 0.5

# PWM
param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 202
param set-default PWM_MAIN_FUNC4 101
param set-default PWM_AUX_FUNC1 201
param set-default PWM_AUX_FUNC2 202
param set-default PWM_AUX_FUNC4 101

# Airspeed parameters
sdp3x start -X -f 400
param set-default ASPD_DO_CHECKS 15
param set-default FW_AIRSPD_MAX 22.0
param set-default FW_AIRSPD_MIN 14.0
param set-default FW_AIRSPD_STALL 12.0
param set-default FW_AIRSPD_TRIM 18.0

# Battery parameters
param set-default BAT1_N_CELLS 4
param set-default BAT1_R_INTERNAL 0.0050
param set-default BAT1_V_EMPTY 3.6000
param set-default BAT1_V_LOAD_DROP 0.1000

param set-default BAT2_R_INTERNAL 0.0050
param set-default BAT2_V_EMPTY 3.6000
param set-default BAT2_V_LOAD_DROP 0.1000

# Disable internal magnetometer
param set CAL_MAG0_PRIO 0

# Launch detection
param set-default FW_LAUN_DETCN_ON 1

# Maximum manual roll angle
param set-default FW_MAN_R_MAX 60.0

# Rate control
param set-default FW_RR_IMAX 0.4000
param set-default FW_YR_IMAX 0.4000

# Misc
param set-default RTL_RETURN_ALT 30.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
#!/bin/sh
#
# @name SSRC SCOUT MINI UGV
#
# @url https://global.agilex.ai/products/scout-mini
#
# @type Rover
# @class Rover
#

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

PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=scout_mini}

param set-default SIM_GZ_EN 1

param set-default CA_AIRFRAME 6

param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1

param set IMU_GYRO_CUTOFF 60
param set IMU_DGYRO_CUTOFF 30

param set-default SYS_HAS_BARO 0

param set-default BAT1_N_CELLS 4

param set-default MIS_TAKEOFF_ALT 0.01

param set-default NAV_ACC_RAD 0.5 # reached when within 0.5m of waypoint

# Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128

# EKF2
param set-default EKF2_GBIAS_INIT 0.01
param set-default EKF2_ANGERR_INIT 0.01
param set-default EKF2_MAG_TYPE 1
param set-default EKF2_REQ_SACC 1.0
param set-default EKF2_REQ_VDRIFT 0.4
param set-default EKF2_REQ_HDRIFT 0.2


#################################
# Rover Position Control Module #
#################################

param set-default GND_SP_CTRL_MODE 1
param set-default GND_L1_DIST 5
param set-default GND_L1_PERIOD 3
param set-default GND_THR_CRUISE 1
param set-default GND_THR_MAX 1

# Because this is differential drive, it can make a turn with radius 0.
# This corresponds to a turn angle of pi radians.
# If a special case is made for differential-drive, this will need to change.
param set-default GND_MAX_ANG 3.142
param set-default GND_WHEEL_BASE 0.45

# TODO: Set to -1.0, to allow reversing. This will require many changes in the codebase
# to support negative throttle.
param set-default GND_THR_MIN 0
param set-default GND_SPEED_P 0.4
param set-default GND_SPEED_I 1
param set-default GND_SPEED_D 0.001
param set-default GND_SPEED_IMAX 1
param set-default GND_SPEED_MAX 1
param set-default GND_SPEED_THR_SC 1
4 changes: 4 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,10 @@ px4_add_romfs_files(
4004_gz_standard_vtol
4005_gz_x500_vision
4006_gz_px4vision
4401_gz_ssrc_fog_x
4430_gz_ssrc_striver_mini
4440_gz_ssrc_skywalker_x8
50005_gz_ssrc_scout_mini_rover

6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post
Expand Down
Loading

0 comments on commit 782e756

Please sign in to comment.