Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

New GZ SIM compatible SITL build and rover fixes #532

Merged
merged 8 commits into from
Oct 30, 2023
Merged
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
5 changes: 2 additions & 3 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna
Original file line number Diff line number Diff line change
Expand Up @@ -11,14 +11,13 @@ PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=rc_cessna}

param set-default SIM_GZ_EN 1
param set-default SIM_GZ_RUN_GZSIM 0

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



param set-default FW_LND_ANG 8

param set-default NPFG_PERIOD 12
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,10 @@ PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol}

param set-default SIM_GZ_EN 1
param set-default SIM_GZ_RUN_GZSIM 0

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

Expand Down
71 changes: 71 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,71 @@
#!/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 SIM_GZ_RUN_GZSIM 0

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_EC_FUNC1 101
param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_EC_FUNC3 103
param set-default SIM_GZ_EC_FUNC4 104

param set-default SIM_GZ_EC_MIN1 150
param set-default SIM_GZ_EC_MIN2 150
param set-default SIM_GZ_EC_MIN3 150
param set-default SIM_GZ_EC_MIN4 150

param set-default SIM_GZ_EC_MAX1 1000
param set-default SIM_GZ_EC_MAX2 1000
param set-default SIM_GZ_EC_MAX3 1000
param set-default SIM_GZ_EC_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
Original file line number Diff line number Diff line change
@@ -0,0 +1,95 @@
#!/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
param set-default SIM_GZ_RUN_GZSIM 0

param set-default SENS_EN_GPSSIM 1
param set-default SENS_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 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

# GZ SIM
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_MIN1 0
param set-default SIM_GZ_EC_MAX1 1000

param set-default SIM_GZ_SV_FUNC1 201
param set-default SIM_GZ_SV_FUNC2 202

# Airspeed parameters
param set-default ASPD_PRIMARY 1
# 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

# Maximum landing slope angle in deg
param set-default FW_LND_ANG 8

# RC loss failsafe to HOLD mode
param set-default COM_RC_IN_MODE 1

# Fixed wing control
# Pitch rate
param set-default FW_PR_P 0.9
param set-default FW_PR_FF 0.5
param set-default FW_PR_I 0.5
param set-default TRIM_PITCH -0.15
# Pitch angle in deg
param set-default FW_PSP_OFF 0
param set-default FW_P_LIM_MIN -15
# Roll rate
param set-default FW_RR_FF 0.5
param set-default FW_RR_P 0.3
param set-default FW_RR_I 0.5
# Yaw rate
param set-default FW_YR_FF 0.5
param set-default FW_YR_P 0.6
param set-default FW_YR_I 0.5
# Throttle limit
# param set-default FW_THR_MAX 0.6
# param set-default FW_THR_MIN 0.05
# param set-default FW_THR_TRIM 0.25
# Climb and sink rate
param set-default FW_T_CLMB_MAX 8
param set-default FW_T_SINK_MAX 2.7
param set-default FW_T_SINK_MIN 2.2

# Navigation
param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2

# Misc
param set-default MIS_TAKEOFF_ALT 30.0
param set-default RTL_RETURN_ALT 30.0

# Disable internal magnetometer
param set CAL_MAG0_PRIO 0

# Catapult launch with acc threshold trigger
param set-default FW_LAUN_DETCN_ON 1
param set-default FW_THR_IDLE 0.1 # needs to be running before throw as that's how gazebo detects arming
param set-default FW_LAUN_AC_THLD 10
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
#!/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 SIM_GZ_RUN_GZSIM 0

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_MAX 3.0
param set-default GND_SPEED_TRIM 3.0
param set-default GND_SPEED_THR_SC 1.0
param set-default GND_VEL_CTRL 1
param set-default GND_ANG_VEL_CTRL 1
param set-default GND_ACC_LIMIT 10
param set-default GND_DEC_LIMIT 50
3 changes: 3 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,9 @@ px4_add_romfs_files(
4004_gz_standard_vtol
4005_gz_x500_vision
4006_gz_px4vision
4401_gz_ssrc_fog_x
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