forked from Archive/PX4-Autopilot
SITL Gazebo classic make airframes simulator specific
This commit is contained in:
parent
97c8a60d67
commit
618288cca9
|
@ -81,7 +81,7 @@ jobs:
|
|||
env:
|
||||
PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}}
|
||||
DONT_RUN: 1
|
||||
run: make px4_sitl_default gazebo mavsdk_tests
|
||||
run: make px4_sitl_default sitl_gazebo mavsdk_tests
|
||||
- name: ccache post-run mavsdk_tests
|
||||
run: ccache -s
|
||||
|
||||
|
|
|
@ -282,7 +282,10 @@ if(${PX4_PLATFORM} STREQUAL "posix")
|
|||
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
||||
set(CMAKE_ENABLE_EXPORTS ON)
|
||||
|
||||
if(CMAKE_BUILD_TYPE MATCHES "Coverage")
|
||||
include(coverage)
|
||||
endif()
|
||||
|
||||
include(sanitizers)
|
||||
|
||||
# Define GNU standard installation directories
|
||||
|
|
|
@ -0,0 +1,33 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (foggy_lidar)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.1515
|
||||
param set-default CA_ROTOR0_PY 0.245
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.1515
|
||||
param set-default CA_ROTOR1_PY -0.1875
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.1515
|
||||
param set-default CA_ROTOR2_PY -0.245
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.1515
|
||||
param set-default CA_ROTOR3_PY 0.1875
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
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 EKF2_RNG_A_HMAX 10
|
||||
|
|
@ -1,11 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (foggy_lidar)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10016_iris
|
||||
|
||||
param set-default EKF2_RNG_A_HMAX 10
|
||||
|
|
@ -0,0 +1,47 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Optical Flow)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.1515
|
||||
param set-default CA_ROTOR0_PY 0.245
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.1515
|
||||
param set-default CA_ROTOR1_PY -0.1875
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.1515
|
||||
param set-default CA_ROTOR2_PY -0.245
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.1515
|
||||
param set-default CA_ROTOR3_PY 0.1875
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
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
|
||||
|
||||
# EKF2
|
||||
param set-default EKF2_AID_MASK 2
|
||||
param set-default EKF2_GPS_CTRL 0
|
||||
param set-default EKF2_EVP_NOISE 0.05
|
||||
param set-default EKF2_EVA_NOISE 0.05
|
||||
|
||||
# LPE: Flow-only mode
|
||||
param set-default LPE_FUSION 242
|
||||
param set-default LPE_FAKE_ORIGIN 1
|
||||
|
||||
param set-default MPC_ALT_MODE 2
|
||||
|
||||
param set-default SENS_FLOW_ROT 6
|
||||
param set-default SENS_FLOW_MINHGT 0.7
|
||||
param set-default SENS_FLOW_MAXHGT 3.0
|
||||
param set-default SENS_FLOW_MAXR 2.5
|
|
@ -1,25 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Optical Flow)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10016_iris
|
||||
|
||||
# EKF2
|
||||
param set-default EKF2_AID_MASK 2
|
||||
param set-default EKF2_GPS_CTRL 0
|
||||
param set-default EKF2_EVP_NOISE 0.05
|
||||
param set-default EKF2_EVA_NOISE 0.05
|
||||
|
||||
# LPE: Flow-only mode
|
||||
param set-default LPE_FUSION 242
|
||||
param set-default LPE_FAKE_ORIGIN 1
|
||||
|
||||
param set-default MPC_ALT_MODE 2
|
||||
|
||||
param set-default SENS_FLOW_ROT 6
|
||||
param set-default SENS_FLOW_MINHGT 0.7
|
||||
param set-default SENS_FLOW_MAXHGT 3.0
|
||||
param set-default SENS_FLOW_MAXR 2.5
|
|
@ -0,0 +1,38 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (irlock)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.1515
|
||||
param set-default CA_ROTOR0_PY 0.245
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.1515
|
||||
param set-default CA_ROTOR1_PY -0.1875
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.1515
|
||||
param set-default CA_ROTOR2_PY -0.245
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.1515
|
||||
param set-default CA_ROTOR3_PY 0.1875
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
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
|
||||
|
||||
# enable fusion of landing target velocity
|
||||
param set-default LTEST_MODE 1
|
||||
param set-default PLD_HACC_RAD 0.1
|
||||
param set-default RTL_PLD_MD 2
|
||||
|
||||
# Start up Landing Target Estimator module
|
||||
landing_target_estimator start
|
|
@ -1,16 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (irlock)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10016_iris
|
||||
|
||||
# enable fusion of landing target velocity
|
||||
param set-default LTEST_MODE 1
|
||||
param set-default PLD_HACC_RAD 0.1
|
||||
param set-default RTL_PLD_MD 2
|
||||
|
||||
# Start up Landing Target Estimator module
|
||||
landing_target_estimator start
|
|
@ -0,0 +1,33 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (rplidar)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.1515
|
||||
param set-default CA_ROTOR0_PY 0.245
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.1515
|
||||
param set-default CA_ROTOR1_PY -0.1875
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.1515
|
||||
param set-default CA_ROTOR2_PY -0.245
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.1515
|
||||
param set-default CA_ROTOR3_PY 0.1875
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
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 LPE_FUSION 242
|
||||
|
|
@ -1,11 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (rplidar)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10016_iris
|
||||
|
||||
param set-default LPE_FUSION 242
|
||||
|
|
@ -0,0 +1,34 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Obstacle Avoidance)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.1515
|
||||
param set-default CA_ROTOR0_PY 0.245
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.1515
|
||||
param set-default CA_ROTOR1_PY -0.1875
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.1515
|
||||
param set-default CA_ROTOR2_PY -0.245
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.1515
|
||||
param set-default CA_ROTOR3_PY 0.1875
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
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 COM_OBS_AVOID 1
|
||||
param set-default MPC_XY_CRUISE 5.0
|
||||
|
|
@ -1,12 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Obstacle Avoidance)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10016_iris
|
||||
|
||||
param set-default COM_OBS_AVOID 1
|
||||
param set-default MPC_XY_CRUISE 5.0
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Optical Flow)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.1515
|
||||
param set-default CA_ROTOR0_PY 0.245
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.1515
|
||||
param set-default CA_ROTOR1_PY -0.1875
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.1515
|
||||
param set-default CA_ROTOR2_PY -0.245
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.1515
|
||||
param set-default CA_ROTOR3_PY 0.1875
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
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
|
||||
|
||||
# EKF2
|
||||
param set-default EKF2_AID_MASK 2
|
||||
param set-default EKF2_GPS_CTRL 0
|
||||
|
||||
# LPE: Flow-only mode
|
||||
param set-default LPE_FUSION 242
|
||||
param set-default LPE_FAKE_ORIGIN 1
|
||||
|
||||
param set-default MPC_ALT_MODE 2
|
|
@ -1,18 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Optical Flow)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10016_iris
|
||||
|
||||
# EKF2
|
||||
param set-default EKF2_AID_MASK 2
|
||||
param set-default EKF2_GPS_CTRL 0
|
||||
|
||||
# LPE: Flow-only mode
|
||||
param set-default LPE_FUSION 242
|
||||
param set-default LPE_FAKE_ORIGIN 1
|
||||
|
||||
param set-default MPC_ALT_MODE 2
|
|
@ -1,13 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Vision Velocity)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10016_iris
|
||||
|
||||
# EKF2: Vision velocity and heading
|
||||
param set-default EKF2_AID_MASK 272
|
||||
param set-default EKF2_EV_DELAY 5
|
||||
param set-default EKF2_GPS_CTRL 0
|
|
@ -0,0 +1,33 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Dual GPS)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.1515
|
||||
param set-default CA_ROTOR0_PY 0.245
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.1515
|
||||
param set-default CA_ROTOR1_PY -0.1875
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.1515
|
||||
param set-default CA_ROTOR2_PY -0.245
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.1515
|
||||
param set-default CA_ROTOR3_PY 0.1875
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
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
|
||||
|
||||
# EKF2: Multi GPS blending
|
||||
param set-default SENS_GPS_MASK 7
|
|
@ -1,11 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor SITL (Dual GPS)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10016_iris
|
||||
|
||||
# EKF2: Multi GPS blending
|
||||
param set-default SENS_GPS_MASK 7
|
|
@ -0,0 +1,81 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with camera
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
param set-default EKF2_MAG_ACCLIM 0
|
||||
param set-default EKF2_MAG_YAWLIM 0
|
||||
|
||||
param set-default FW_LND_AIRSPD_SC 1
|
||||
param set-default FW_LND_ANG 8
|
||||
|
||||
param set-default FW_L1_PERIOD 12
|
||||
|
||||
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
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
param set-default FW_RR_FF 0.5
|
||||
param set-default FW_RR_P 0.3
|
||||
param set-default FW_RR_I 0.5
|
||||
|
||||
param set-default FW_YR_FF 0.5
|
||||
param set-default FW_YR_P 0.6
|
||||
param set-default FW_YR_I 0.5
|
||||
|
||||
param set-default FW_SPOILERS_LND 0.4
|
||||
|
||||
param set-default FW_THR_MAX 0.6
|
||||
param set-default FW_THR_MIN 0.05
|
||||
param set-default FW_THR_TRIM 0.25
|
||||
|
||||
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
|
||||
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_LTRMIN_ALT 30
|
||||
param set-default MIS_TAKEOFF_ALT 30
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
param set-default CA_AIRFRAME 1
|
||||
|
||||
param set-default CA_ROTOR_COUNT 1
|
||||
param set-default CA_ROTOR0_PX 0.3
|
||||
|
||||
param set-default CA_SV_CS_COUNT 6
|
||||
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||
param set-default CA_SV_CS0_TYPE 1
|
||||
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||
param set-default CA_SV_CS1_TYPE 2
|
||||
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||
param set-default CA_SV_CS2_TYPE 3
|
||||
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||
param set-default CA_SV_CS3_TYPE 4
|
||||
param set-default CA_SV_CS4_TYPE 9
|
||||
param set-default CA_SV_CS5_TYPE 10
|
||||
param set-default PWM_MAIN_FUNC3 204
|
||||
param set-default PWM_MAIN_FUNC4 205
|
||||
param set-default PWM_MAIN_FUNC5 101
|
||||
param set-default PWM_MAIN_FUNC6 201
|
||||
param set-default PWM_MAIN_FUNC7 202
|
||||
param set-default PWM_MAIN_FUNC8 203
|
||||
param set-default PWM_MAIN_FUNC9 206
|
||||
param set-default PWM_MAIN_REV 256
|
||||
|
||||
# Camera trigger interface is MAVLink
|
||||
param set-default TRIG_INTERFACE 3
|
||||
|
||||
# Distance trigger mode enabled
|
||||
param set-default TRIG_MODE 4
|
|
@ -1,12 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with camera
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/1030_plane
|
||||
|
||||
# Camera trigger interface is MAVLink
|
||||
param set-default TRIG_INTERFACE 3
|
||||
|
||||
# Distance trigger mode enabled
|
||||
param set-default TRIG_MODE 4
|
|
@ -0,0 +1,78 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with catapult
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
param set-default EKF2_MAG_ACCLIM 0
|
||||
param set-default EKF2_MAG_YAWLIM 0
|
||||
|
||||
param set-default FW_LND_AIRSPD_SC 1
|
||||
param set-default FW_LND_ANG 8
|
||||
|
||||
param set-default FW_L1_PERIOD 12
|
||||
|
||||
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
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
param set-default FW_RR_FF 0.5
|
||||
param set-default FW_RR_P 0.3
|
||||
param set-default FW_RR_I 0.5
|
||||
|
||||
param set-default FW_YR_FF 0.5
|
||||
param set-default FW_YR_P 0.6
|
||||
param set-default FW_YR_I 0.5
|
||||
|
||||
param set-default FW_SPOILERS_LND 0.4
|
||||
|
||||
param set-default FW_THR_MAX 0.6
|
||||
param set-default FW_THR_MIN 0.05
|
||||
param set-default FW_THR_TRIM 0.25
|
||||
|
||||
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
|
||||
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_LTRMIN_ALT 30
|
||||
param set-default MIS_TAKEOFF_ALT 30
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
param set-default CA_AIRFRAME 1
|
||||
|
||||
param set-default CA_ROTOR_COUNT 1
|
||||
param set-default CA_ROTOR0_PX 0.3
|
||||
|
||||
param set-default CA_SV_CS_COUNT 6
|
||||
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||
param set-default CA_SV_CS0_TYPE 1
|
||||
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||
param set-default CA_SV_CS1_TYPE 2
|
||||
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||
param set-default CA_SV_CS2_TYPE 3
|
||||
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||
param set-default CA_SV_CS3_TYPE 4
|
||||
param set-default CA_SV_CS4_TYPE 9
|
||||
param set-default CA_SV_CS5_TYPE 10
|
||||
param set-default PWM_MAIN_FUNC3 204
|
||||
param set-default PWM_MAIN_FUNC4 205
|
||||
param set-default PWM_MAIN_FUNC5 101
|
||||
param set-default PWM_MAIN_FUNC6 201
|
||||
param set-default PWM_MAIN_FUNC7 202
|
||||
param set-default PWM_MAIN_FUNC8 203
|
||||
param set-default PWM_MAIN_FUNC9 206
|
||||
param set-default PWM_MAIN_REV 256
|
||||
|
||||
param set-default RWTO_TKOFF 0
|
||||
|
|
@ -1,9 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with catapult
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/1030_plane
|
||||
|
||||
param set-default RWTO_TKOFF 0
|
||||
|
|
@ -57,4 +57,3 @@ param set-default PWM_MAIN_FUNC7 202
|
|||
param set-default PWM_MAIN_FUNC8 203
|
||||
param set-default PWM_MAIN_FUNC9 206
|
||||
param set-default PWM_MAIN_REV 256
|
||||
|
||||
|
|
|
@ -0,0 +1,78 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with catapult
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
param set-default EKF2_MAG_ACCLIM 0
|
||||
param set-default EKF2_MAG_YAWLIM 0
|
||||
|
||||
param set-default FW_LND_AIRSPD_SC 1
|
||||
param set-default FW_LND_ANG 8
|
||||
|
||||
param set-default FW_L1_PERIOD 12
|
||||
|
||||
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
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
param set-default FW_RR_FF 0.5
|
||||
param set-default FW_RR_P 0.3
|
||||
param set-default FW_RR_I 0.5
|
||||
|
||||
param set-default FW_YR_FF 0.5
|
||||
param set-default FW_YR_P 0.6
|
||||
param set-default FW_YR_I 0.5
|
||||
|
||||
param set-default FW_SPOILERS_LND 0.4
|
||||
|
||||
param set-default FW_THR_MAX 0.6
|
||||
param set-default FW_THR_MIN 0.05
|
||||
param set-default FW_THR_TRIM 0.25
|
||||
|
||||
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
|
||||
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_LTRMIN_ALT 30
|
||||
param set-default MIS_TAKEOFF_ALT 30
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
param set-default CA_AIRFRAME 1
|
||||
|
||||
param set-default CA_ROTOR_COUNT 1
|
||||
param set-default CA_ROTOR0_PX 0.3
|
||||
|
||||
param set-default CA_SV_CS_COUNT 6
|
||||
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||
param set-default CA_SV_CS0_TYPE 1
|
||||
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||
param set-default CA_SV_CS1_TYPE 2
|
||||
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||
param set-default CA_SV_CS2_TYPE 3
|
||||
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||
param set-default CA_SV_CS3_TYPE 4
|
||||
param set-default CA_SV_CS4_TYPE 9
|
||||
param set-default CA_SV_CS5_TYPE 10
|
||||
param set-default PWM_MAIN_FUNC3 204
|
||||
param set-default PWM_MAIN_FUNC4 205
|
||||
param set-default PWM_MAIN_FUNC5 101
|
||||
param set-default PWM_MAIN_FUNC6 201
|
||||
param set-default PWM_MAIN_FUNC7 202
|
||||
param set-default PWM_MAIN_FUNC8 203
|
||||
param set-default PWM_MAIN_FUNC9 206
|
||||
param set-default PWM_MAIN_REV 256
|
||||
|
||||
param set-default FW_THR_TRIM 0.0
|
||||
param set-default RWTO_TKOFF 0
|
|
@ -1,9 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with catapult
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/1030_plane
|
||||
|
||||
param set-default FW_THR_TRIM 0.0
|
||||
param set-default RWTO_TKOFF 0
|
|
@ -0,0 +1,65 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
param set-default FW_LND_AIRSPD_SC 1.1
|
||||
param set-default FW_LND_ANG 5
|
||||
param set-default FW_LND_FL_PMIN 9.5
|
||||
param set-default FW_LND_FL_PMAX 20
|
||||
param set-default FW_LND_FLALT 5
|
||||
|
||||
param set-default FW_L1_PERIOD 25
|
||||
|
||||
param set-default FW_PR_FF 0.40
|
||||
param set-default FW_PR_I 0.05
|
||||
param set-default FW_PR_P 0.05
|
||||
|
||||
param set-default FW_R_TC 0.45
|
||||
param set-default FW_RR_FF 0.40
|
||||
param set-default FW_RR_I 0.132
|
||||
param set-default FW_RR_P 0.085
|
||||
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_LTRMIN_ALT 30
|
||||
param set-default MIS_TAKEOFF_ALT 20
|
||||
param set-default MIS_DIST_1WP 2500
|
||||
param set-default MIS_DIST_WPS 10000
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
param set-default RWTO_MAX_PITCH 20
|
||||
|
||||
param set-default RWTO_PSP 8
|
||||
param set-default RWTO_AIRSPD_SCL 1.8
|
||||
|
||||
param set-default CA_AIRFRAME 1
|
||||
|
||||
param set-default CA_ROTOR_COUNT 1
|
||||
param set-default CA_ROTOR0_PX 0.3
|
||||
|
||||
param set-default CA_SV_CS_COUNT 6
|
||||
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||
param set-default CA_SV_CS0_TYPE 1
|
||||
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||
param set-default CA_SV_CS1_TYPE 2
|
||||
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||
param set-default CA_SV_CS2_TYPE 3
|
||||
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||
param set-default CA_SV_CS3_TYPE 4
|
||||
param set-default CA_SV_CS4_TYPE 9
|
||||
param set-default CA_SV_CS5_TYPE 10
|
||||
param set-default PWM_MAIN_FUNC3 204
|
||||
param set-default PWM_MAIN_FUNC4 205
|
||||
param set-default PWM_MAIN_FUNC5 101
|
||||
param set-default PWM_MAIN_FUNC6 201
|
||||
param set-default PWM_MAIN_FUNC7 202
|
||||
param set-default PWM_MAIN_FUNC8 203
|
||||
param set-default PWM_MAIN_FUNC9 206
|
||||
param set-default PWM_MAIN_REV 256
|
|
@ -0,0 +1,93 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Standard VTOL
|
||||
#
|
||||
# @type Standard VTOL
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
# TODO: Enable motor failure detection when the
|
||||
# VTOL no longer reports 0A for all ESCs in SITL
|
||||
param set-default FD_ACT_EN 0
|
||||
param set-default FD_ACT_MOT_TOUT 500
|
||||
|
||||
param set-default CA_AIRFRAME 2
|
||||
|
||||
param set-default CA_ROTOR_COUNT 5
|
||||
param set-default CA_ROTOR0_PX 0.1515
|
||||
param set-default CA_ROTOR0_PY 0.245
|
||||
param set-default CA_ROTOR0_KM 0.05
|
||||
param set-default CA_ROTOR1_PX -0.1515
|
||||
param set-default CA_ROTOR1_PY -0.1875
|
||||
param set-default CA_ROTOR1_KM 0.05
|
||||
param set-default CA_ROTOR2_PX 0.1515
|
||||
param set-default CA_ROTOR2_PY -0.245
|
||||
param set-default CA_ROTOR2_KM -0.05
|
||||
param set-default CA_ROTOR3_PX -0.1515
|
||||
param set-default CA_ROTOR3_PY 0.1875
|
||||
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_ROTOR4_PX 0.2
|
||||
|
||||
param set-default CA_SV_CS_COUNT 3
|
||||
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 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 105
|
||||
param set-default PWM_MAIN_FUNC6 201
|
||||
param set-default PWM_MAIN_FUNC7 202
|
||||
param set-default PWM_MAIN_FUNC8 203
|
||||
|
||||
param set-default FW_L1_PERIOD 12
|
||||
param set-default FW_PR_FF 0.2
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
param set-default FW_RR_FF 0.1
|
||||
param set-default FW_RR_P 0.3
|
||||
param set-default FW_THR_TRIM 0.25
|
||||
param set-default FW_THR_MAX 0.6
|
||||
param set-default FW_THR_MIN 0.05
|
||||
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
|
||||
|
||||
param set-default MC_ROLLRATE_P 0.3
|
||||
param set-default MC_YAW_P 1.6
|
||||
|
||||
param set-default MIS_TAKEOFF_ALT 10
|
||||
|
||||
param set-default MPC_ACC_HOR_MAX 2
|
||||
param set-default MPC_XY_P 0.8
|
||||
param set-default MPC_XY_VEL_P_ACC 3
|
||||
param set-default MPC_XY_VEL_I_ACC 4
|
||||
param set-default MPC_XY_VEL_D_ACC 0.1
|
||||
|
||||
param set-default NAV_ACC_RAD 5
|
||||
|
||||
param set-default VT_FWD_THRUST_EN 4
|
||||
param set-default VT_F_TRANS_THR 0.75
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_FW_MOT_OFFID 1234
|
||||
param set-default VT_B_TRANS_DUR 8
|
||||
param set-default VT_TYPE 2
|
||||
|
||||
|
||||
# Gimbal
|
||||
param set-default PWM_MAIN_FUNC9 420
|
||||
param set-default PWM_MAIN_FUNC10 421
|
||||
param set-default PWM_MAIN_FUNC11 422
|
||||
|
||||
param set-default RC_MAP_AUX1 8
|
||||
param set-default RC_MAP_AUX2 9
|
||||
param set-default RC_MAP_AUX3 10
|
||||
|
|
@ -1,18 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Standard VTOL
|
||||
#
|
||||
# @type Standard VTOL
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/1040_standard_vtol
|
||||
|
||||
# Gimbal
|
||||
param set-default PWM_MAIN_FUNC9 420
|
||||
param set-default PWM_MAIN_FUNC10 421
|
||||
param set-default PWM_MAIN_FUNC11 422
|
||||
|
||||
param set-default RC_MAP_AUX1 8
|
||||
param set-default RC_MAP_AUX2 9
|
||||
param set-default RC_MAP_AUX3 10
|
||||
|
|
@ -0,0 +1,78 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with downward facing LIDAR.
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
param set-default EKF2_MAG_ACCLIM 0
|
||||
param set-default EKF2_MAG_YAWLIM 0
|
||||
|
||||
param set-default FW_LND_AIRSPD_SC 1
|
||||
param set-default FW_LND_ANG 8
|
||||
|
||||
param set-default FW_L1_PERIOD 12
|
||||
|
||||
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
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
param set-default FW_RR_FF 0.5
|
||||
param set-default FW_RR_P 0.3
|
||||
param set-default FW_RR_I 0.5
|
||||
|
||||
param set-default FW_YR_FF 0.5
|
||||
param set-default FW_YR_P 0.6
|
||||
param set-default FW_YR_I 0.5
|
||||
|
||||
param set-default FW_SPOILERS_LND 0.4
|
||||
|
||||
param set-default FW_THR_MAX 0.6
|
||||
param set-default FW_THR_MIN 0.05
|
||||
param set-default FW_THR_TRIM 0.25
|
||||
|
||||
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
|
||||
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_LTRMIN_ALT 30
|
||||
param set-default MIS_TAKEOFF_ALT 30
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
param set-default CA_AIRFRAME 1
|
||||
|
||||
param set-default CA_ROTOR_COUNT 1
|
||||
param set-default CA_ROTOR0_PX 0.3
|
||||
|
||||
param set-default CA_SV_CS_COUNT 6
|
||||
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||
param set-default CA_SV_CS0_TYPE 1
|
||||
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||
param set-default CA_SV_CS1_TYPE 2
|
||||
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||
param set-default CA_SV_CS2_TYPE 3
|
||||
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||
param set-default CA_SV_CS3_TYPE 4
|
||||
param set-default CA_SV_CS4_TYPE 9
|
||||
param set-default CA_SV_CS5_TYPE 10
|
||||
param set-default PWM_MAIN_FUNC3 204
|
||||
param set-default PWM_MAIN_FUNC4 205
|
||||
param set-default PWM_MAIN_FUNC5 101
|
||||
param set-default PWM_MAIN_FUNC6 201
|
||||
param set-default PWM_MAIN_FUNC7 202
|
||||
param set-default PWM_MAIN_FUNC8 203
|
||||
param set-default PWM_MAIN_FUNC9 206
|
||||
param set-default PWM_MAIN_REV 256
|
||||
|
||||
|
||||
param set-default FW_LND_USETER 1
|
|
@ -1,9 +0,0 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with downward facing LIDAR.
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/1030_plane
|
||||
|
||||
param set-default FW_LND_USETER 1
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2020-2023 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
|
@ -32,42 +32,40 @@
|
|||
############################################################################
|
||||
|
||||
px4_add_romfs_files(
|
||||
10016_iris
|
||||
10017_jmavsim_iris
|
||||
10018_iris_foggy_lidar
|
||||
10019_omnicopter
|
||||
10030_px4vision
|
||||
1010_iris_opt_flow
|
||||
1010_iris_opt_flow.post
|
||||
1011_iris_irlock
|
||||
1012_iris_rplidar
|
||||
1013_iris_vision
|
||||
1013_iris_vision.post
|
||||
1015_iris_obs_avoid
|
||||
1015_iris_obs_avoid.post
|
||||
1017_iris_opt_flow_mockup
|
||||
1018_iris_vision_velocity
|
||||
1019_iris_dual_gps
|
||||
1021_uuv_hippocampus
|
||||
1022_uuv_bluerov2_heavy
|
||||
1030_plane
|
||||
1031_plane_cam
|
||||
1032_plane_catapult
|
||||
|
||||
1010_gazebo_iris_opt_flow
|
||||
1010_gazebo_iris_opt_flow.post
|
||||
1011_gazebo_iris_irlock
|
||||
1012_gazebo_iris_rplidar
|
||||
1013_gazebo_iris_vision
|
||||
1013_gazebo_iris_vision.post
|
||||
1015_gazebo_iris_obs_avoid
|
||||
1015_gazebo_iris_obs_avoid.post
|
||||
1017_gazebo_iris_opt_flow_mockup
|
||||
1019_gazebo_iris_dual_gps
|
||||
1021_gazebo_uuv_hippocampus
|
||||
1022_gazebo_uuv_bluerov2_heavy
|
||||
1030_gazebo_plane
|
||||
1031_gazebo_plane_cam
|
||||
1032_gazebo_plane_catapult
|
||||
1033_jsbsim_rascal
|
||||
1034_flightgear_rascal-electric
|
||||
1035_techpod
|
||||
1035_gazebo_techpod
|
||||
1036_jsbsim_malolo
|
||||
1037_believer
|
||||
1038_glider
|
||||
1039_advanced_plane
|
||||
1040_standard_vtol
|
||||
1041_tailsitter
|
||||
1042_tiltrotor
|
||||
1043_standard_vtol_drop
|
||||
1044_plane_lidar
|
||||
1060_rover
|
||||
1061_r1_rover
|
||||
1070_boat
|
||||
1037_gazebo_believer
|
||||
1038_gazebo_glider
|
||||
1039_gazebo_advanced_plane
|
||||
1040_gazebo_standard_vtol
|
||||
1041_gazebo_tailsitter
|
||||
1042_gazebo_tiltrotor
|
||||
1043_gazebo_standard_vtol_drop
|
||||
1044_gazebo_plane_lidar
|
||||
1060_gazebo_rover
|
||||
1061_gazebo_r1_rover
|
||||
1062_flightgear_tf-r1
|
||||
1070_gazebo_boat
|
||||
|
||||
2507_gazebo_cloudship
|
||||
|
||||
3010_jsbsim_quadrotor_x
|
||||
3011_jsbsim_hexarotor_x
|
||||
|
@ -75,10 +73,14 @@ px4_add_romfs_files(
|
|||
4001_gz_x500
|
||||
4002_gz_x500_depth
|
||||
|
||||
2507_cloudship
|
||||
6011_gazebo_typhoon_h480
|
||||
6011_gazebo_typhoon_h480.post
|
||||
|
||||
6011_typhoon_h480
|
||||
6011_typhoon_h480.post
|
||||
10016_gazebo_iris
|
||||
10017_jmavsim_iris
|
||||
10018_gazebo_iris_foggy_lidar
|
||||
10019_gazebo_omnicopter
|
||||
10030_gazebo_px4vision
|
||||
|
||||
10040_sihsim_quadx
|
||||
10041_sihsim_airplane
|
||||
|
|
|
@ -131,7 +131,7 @@ elif [ "$PX4_SIM_MODEL" = "jmavsim_iris" ] || [ "$(param show -q SYS_AUTOSTART)"
|
|||
echo "INFO [init] jMAVSim simulator"
|
||||
|
||||
if jps | grep -i jmavsim; then
|
||||
kill $(jps | grep -i jmavsim | awk '{print $1}') || true
|
||||
kill "$(jps | grep -i jmavsim | awk '{print $1}')" || true
|
||||
sleep 1
|
||||
fi
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/bash
|
||||
# run multiple instances of the 'px4' binary, with the gazebo SITL simulation
|
||||
# It assumes px4 is already built, with 'make px4_sitl_default gazebo'
|
||||
# It assumes px4 is already built, with 'make px4_sitl_default sitl_gazebo'
|
||||
|
||||
# The simulator is expected to send to TCP port 4560+i for i in [0, N-1]
|
||||
# For example gazebo can be run like this:
|
||||
|
@ -69,7 +69,7 @@ num_vehicles=${NUM_VEHICLES:=3}
|
|||
world=${WORLD:=empty}
|
||||
target=${TARGET:=px4_sitl_default}
|
||||
vehicle_model=${VEHICLE_MODEL:="iris"}
|
||||
export PX4_SIM_MODEL=${vehicle_model}
|
||||
export PX4_SIM_MODEL=gazebo_${vehicle_model}
|
||||
|
||||
echo ${SCRIPT}
|
||||
SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
|
||||
|
@ -126,7 +126,7 @@ else
|
|||
|
||||
m=0
|
||||
while [ $m -lt ${target_number} ]; do
|
||||
export PX4_SIM_MODEL=${target_vehicle}
|
||||
export PX4_SIM_MODEL=gazebo_${target_vehicle}
|
||||
spawn_model ${target_vehicle}${LABEL} $n $target_x $target_y
|
||||
m=$(($m + 1))
|
||||
n=$(($n + 1))
|
||||
|
|
|
@ -67,7 +67,7 @@ fi
|
|||
# be running from last time
|
||||
pkill -x gazebo || true
|
||||
|
||||
export PX4_SIM_MODEL=${model}
|
||||
export PX4_SIM_MODEL=gazebo_${model}
|
||||
export PX4_SIM_WORLD=${world}
|
||||
|
||||
SIM_PID=0
|
||||
|
@ -75,10 +75,6 @@ SIM_PID=0
|
|||
if [ -x "$(command -v gazebo)" ]; then
|
||||
# Get the model name
|
||||
model_name="${model}"
|
||||
# Check if a 'modelname-gen.sdf' file exist for the models using jinja and generating the SDF files
|
||||
if [ -f "${src_path}/Tools/simulation/gazebo/sitl_gazebo/models/${model}/${model}-gen.sdf" ]; then
|
||||
model_name="${model}-gen"
|
||||
fi
|
||||
|
||||
# Set the plugin path so Gazebo finds our model and sim
|
||||
source "$src_path/Tools/simulation/gazebo/setup_gazebo.bash" "${src_path}" "${build_path}"
|
||||
|
|
|
@ -19,7 +19,7 @@ pkill -x px4 || true
|
|||
|
||||
sleep 1
|
||||
|
||||
export PX4_SIM_MODEL=iris
|
||||
export PX4_SIM_MODEL=gazebo_iris
|
||||
|
||||
n=0
|
||||
while [ $n -lt $sitl_num ]; do
|
||||
|
|
|
@ -14,7 +14,7 @@
|
|||
<arg name="vehicle" default="iris"/>
|
||||
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
|
||||
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
|
||||
<env name="PX4_SIM_MODEL" value="gazebo_$(arg vehicle)" />
|
||||
|
||||
<!-- gazebo configs -->
|
||||
<arg name="gui" default="true"/>
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
<arg name="ID" default="0"/>
|
||||
<arg name="interactive" default="true"/>
|
||||
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
|
||||
<env name="PX4_SIM_MODEL" value="gazebo_$(arg vehicle)" />
|
||||
<arg unless="$(arg interactive)" name="px4_command_arg1" value="-d"/>
|
||||
<arg if="$(arg interactive)" name="px4_command_arg1" value=""/>
|
||||
<node name="sitl_$(arg ID)" pkg="px4" type="px4" output="screen" args="$(find px4)/build/px4_sitl_default/etc -s etc/init.d-posix/rcS -i $(arg ID) $(arg px4_command_arg1)">
|
||||
|
|
|
@ -13,7 +13,7 @@
|
|||
<arg name="est" default="ekf2"/>
|
||||
<arg name="vehicle" default="iris"/>
|
||||
<arg name="ID" default="1"/>
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
|
||||
<env name="PX4_SIM_MODEL" value="gazebo_$(arg vehicle)" />
|
||||
<arg name="mavlink_udp_port" default="14560"/>
|
||||
<arg name="mavlink_tcp_port" default="4560"/>
|
||||
<arg name="gst_udp_port" default="5600"/>
|
||||
|
|
|
@ -13,7 +13,7 @@
|
|||
<arg name="est" default="ekf2"/>
|
||||
<arg name="vehicle" default="plane"/>
|
||||
<arg name="ID" default="1"/>
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
|
||||
<env name="PX4_SIM_MODEL" value="gazebo_$(arg vehicle)" />
|
||||
<arg name="mavlink_udp_port" default="14560"/>
|
||||
<arg name="mavlink_tcp_port" default="4560"/>
|
||||
<!-- PX4 configs -->
|
||||
|
|
|
@ -99,7 +99,7 @@
|
|||
"environment": [
|
||||
{
|
||||
"name": "PX4_SIM_MODEL",
|
||||
"value": "iris"
|
||||
"value": "gazebo_iris"
|
||||
}
|
||||
],
|
||||
"externalConsole": false,
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2015-2018 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2015-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -345,10 +345,7 @@ int main(int argc, char **argv)
|
|||
|
||||
ret = run_startup_script(commands_file, absolute_binary_path, instance);
|
||||
|
||||
if (ret != 0) {
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (ret == 0) {
|
||||
// We now block here until we need to exit.
|
||||
if (pxh_off) {
|
||||
wait_to_exit();
|
||||
|
@ -357,10 +354,24 @@ int main(int argc, char **argv)
|
|||
px4_daemon::Pxh pxh;
|
||||
pxh.run_pxh();
|
||||
}
|
||||
}
|
||||
|
||||
// delete lock
|
||||
const std::string file_lock_path = std::string(LOCK_FILE_PATH) + '-' + std::to_string(instance);
|
||||
int fd_flock = open(file_lock_path.c_str(), O_RDWR, 0666);
|
||||
|
||||
if (fd_flock >= 0) {
|
||||
unlink(file_lock_path.c_str());
|
||||
flock(fd_flock, LOCK_UN);
|
||||
close(fd_flock);
|
||||
}
|
||||
|
||||
if (ret != 0) {
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
std::string cmd("shutdown");
|
||||
px4_daemon::Pxh::process_line(cmd, true);
|
||||
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
|
@ -453,7 +464,7 @@ void register_sig_handler()
|
|||
// SIGINT
|
||||
struct sigaction sig_int {};
|
||||
sig_int.sa_handler = sig_int_handler;
|
||||
sig_int.sa_flags = 0;// not SA_RESTART!
|
||||
sig_int.sa_flags = 0; // not SA_RESTART!
|
||||
|
||||
// SIGPIPE
|
||||
// We want to ignore if a PIPE has been closed.
|
||||
|
|
|
@ -228,6 +228,8 @@ Server::_server_main()
|
|||
_unlock();
|
||||
}
|
||||
|
||||
std::string sock_path = get_socket_path(_instance_id);
|
||||
unlink(sock_path.c_str());
|
||||
close(_fd);
|
||||
}
|
||||
|
||||
|
|
|
@ -62,7 +62,6 @@ set(debuggers
|
|||
)
|
||||
|
||||
set(models
|
||||
none
|
||||
advanced_plane
|
||||
believer
|
||||
boat
|
||||
|
@ -77,7 +76,6 @@ set(models
|
|||
iris_opt_flow_mockup
|
||||
iris_rplidar
|
||||
iris_vision
|
||||
nxp_cupcar
|
||||
omnicopter
|
||||
plane
|
||||
plane_cam
|
||||
|
@ -86,7 +84,6 @@ set(models
|
|||
px4vision
|
||||
r1_rover
|
||||
rover
|
||||
shell
|
||||
standard_vtol
|
||||
standard_vtol_drop
|
||||
tailsitter
|
||||
|
@ -109,8 +106,62 @@ set(worlds
|
|||
yosemite
|
||||
)
|
||||
|
||||
# find corresponding airframes
|
||||
file(GLOB gazebo_airframes
|
||||
RELATIVE ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes
|
||||
${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_gazebo_*
|
||||
)
|
||||
|
||||
# remove any .post files
|
||||
foreach(gazebo_airframe IN LISTS gazebo_airframes)
|
||||
if(gazebo_airframe MATCHES ".post")
|
||||
list(REMOVE_ITEM gazebo_airframes ${gazebo_airframe})
|
||||
endif()
|
||||
endforeach()
|
||||
list(REMOVE_DUPLICATES gazebo_airframes)
|
||||
|
||||
foreach(gazebo_airframe IN LISTS gazebo_airframes)
|
||||
set(model_only)
|
||||
string(REGEX REPLACE ".*_gazebo_" "" model_only ${gazebo_airframe})
|
||||
|
||||
if(EXISTS "${PX4_SOURCE_DIR}/Tools/simulation/gazebo/sitl_gazebo/models/${model_only}")
|
||||
|
||||
if((EXISTS "${PX4_SOURCE_DIR}/Tools/simulation/gazebo/sitl_gazebo/models/${model_only}/${model_only}.sdf")
|
||||
OR (EXISTS "${PX4_SOURCE_DIR}/Tools/simulation/gazebo/sitl_gazebo/models/${model_only}/${model_only}.sdf.jinja"))
|
||||
#message(STATUS "SDF file found for ${model_only}")
|
||||
else()
|
||||
message(WARNING "No SDF file found for ${model_only}")
|
||||
endif()
|
||||
|
||||
else()
|
||||
message(WARNING "model directory ${PX4_SOURCE_DIR}/Tools/simulation/gazebo/sitl_gazebo/models/${model_only} not found")
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
foreach(debugger ${debuggers})
|
||||
foreach(model ${models})
|
||||
|
||||
# match model to airframe
|
||||
set(airframe_model_only)
|
||||
set(airframe_sys_autostart)
|
||||
set(gazebo_airframe_found)
|
||||
foreach(gazebo_airframe IN LISTS gazebo_airframes)
|
||||
|
||||
string(REGEX REPLACE ".*_gazebo_" "" airframe_model_only ${gazebo_airframe})
|
||||
string(REGEX REPLACE "_gazebo_.*" "" airframe_sys_autostart ${gazebo_airframe})
|
||||
|
||||
if(model STREQUAL ${airframe_model_only})
|
||||
set(gazebo_airframe_found ${gazebo_airframe})
|
||||
break()
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
if(gazebo_airframe_found)
|
||||
#message(STATUS "gazebo model: ${model} (${airframe_model_only}), airframe: ${gazebo_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
|
||||
else()
|
||||
message(WARNING "gazebo missing model: ${model} (${airframe_model_only}), airframe: ${gazebo_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
|
||||
endif()
|
||||
|
||||
foreach(world ${worlds})
|
||||
if(world STREQUAL "none")
|
||||
if(debugger STREQUAL "none")
|
||||
|
|
|
@ -164,7 +164,7 @@ class Px4Runner(Runner):
|
|||
os.path.join(workspace_dir, "test_data"),
|
||||
"-d"
|
||||
]
|
||||
self.env["PX4_SIM_MODEL"] = self.model
|
||||
self.env["PX4_SIM_MODEL"] = "gazebo_" + self.model
|
||||
self.env["PX4_SIM_SPEED_FACTOR"] = str(speed_factor)
|
||||
self.debugger = debugger
|
||||
self.clear_rootfs()
|
||||
|
@ -275,13 +275,6 @@ class GzmodelspawnRunner(Runner):
|
|||
PX4_GAZEBO_MODELS,
|
||||
self.model, self.model + ".sdf")
|
||||
|
||||
elif os.path.isfile(os.path.join(workspace_dir,
|
||||
PX4_GAZEBO_MODELS,
|
||||
self.model, self.model + "-gen.sdf")):
|
||||
|
||||
model_path = os.path.join(workspace_dir,
|
||||
PX4_GAZEBO_MODELS,
|
||||
self.model, self.model + "-gen.sdf")
|
||||
else:
|
||||
raise Exception("Model not found")
|
||||
|
||||
|
|
Loading…
Reference in New Issue