Compare commits

...

1 Commits

Author SHA1 Message Date
Daniel Agar 331cefc1d1 init.d-posix: make all simulation airframes simulator specific 2022-09-01 22:00:22 -04:00
91 changed files with 1242 additions and 474 deletions
+1 -1
View File
@@ -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
-39
View File
@@ -49,45 +49,6 @@
"group": "test"
}
},
{
"label": "jmavsim build",
"type": "shell",
"command": "ant create_run_jar copy_res",
"options": {
"cwd": "${workspaceFolder}/Tools/simulation/jmavsim/jMAVSim"
},
"problemMatcher": [],
"presentation":{
"echo": true,
"reveal": "never",
"focus": false,
"panel": "shared",
"showReuseMessage": false,
"clear": false,
}
},
{
"label": "jmavsim",
"type": "shell",
"dependsOn": "jmavsim build",
"command": "java -Djava.ext.dirs= -jar jmavsim_run.jar -r 250 -lockstep -tcp localhost:4560 -qgc",
"options": {
"cwd": "${workspaceFolder}/Tools/simulation/jmavsim/jMAVSim/out/production",
"env": {
"PX4_SIM_SPEED_FACTOR": "1"
}
},
"isBackground": true,
"presentation": {
"echo": true,
"reveal": "never",
"focus": false,
"panel": "shared",
"showReuseMessage": false,
"clear": false
},
"problemMatcher": []
},
{
"label": "jmavsim kill",
"type": "shell",
+4 -1
View File
@@ -296,7 +296,10 @@ if(${PX4_PLATFORM} STREQUAL "posix")
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
set(CMAKE_ENABLE_EXPORTS ON)
include(coverage)
if(CMAKE_BUILD_TYPE MATCHES "Coverage")
include(coverage)
endif()
include(sanitizers)
# Define GNU standard installation directories
@@ -0,0 +1,34 @@
#!/bin/sh
#
# @name 3DR Iris Quadrotor SITL
#
# @type Quadrotor Wide
#
# @maintainer Julian Oes <julian@oes.ch>
#
. ${R}etc/init.d/rc.mc_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=jmavsim}
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
@@ -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
@@ -41,4 +41,3 @@ param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set SIH_VEHICLE_TYPE 0
@@ -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,42 @@
#!/bin/sh
#
# @name 3DR Iris Quadrotor SITL (Vision)
#
# @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: Vision position and heading
param set-default EKF2_AID_MASK 24
param set-default EKF2_EV_DELAY 5
param set-default EKF2_GPS_CTRL 0
# LPE: Vision + baro
param set-default LPE_FUSION 132
# AEQ: External heading set to use vision input
param set-default ATT_EXT_HDG_M 1
@@ -1,20 +0,0 @@
#!/bin/sh
#
# @name 3DR Iris Quadrotor SITL (Vision)
#
# @type Quadrotor Wide
#
. ${R}etc/init.d-posix/airframes/10016_iris
# EKF2: Vision position and heading
param set-default EKF2_AID_MASK 24
param set-default EKF2_EV_DELAY 5
param set-default EKF2_GPS_CTRL 0
# LPE: Vision + baro
param set-default LPE_FUSION 132
# AEQ: External heading set to use vision input
param set-default ATT_EXT_HDG_M 1
@@ -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
@@ -63,4 +63,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
@@ -32,54 +32,58 @@
############################################################################
px4_add_romfs_files(
10016_iris
10018_iris_foggy_lidar
10019_omnicopter
10030_px4vision
10040_quadx
10041_airplane
10042_xvert
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
1033_rascal
1034_rascal-electric
1035_techpod
1036_malolo
1037_believer
1038_glider
1040_standard_vtol
1041_tailsitter
1042_tiltrotor
1043_standard_vtol_drop
1044_plane_lidar
1060_rover
1061_r1_rover
1062_tf-r1
1070_boat
3010_quadrotor_x
3011_hexarotor_x
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_gazebo_techpod
1036_jsbsim_malolo
1037_gazebo_believer
1038_gazebo_glider
1039_flightgear_rascal
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
4001_x500
2507_gazebo_cloudship
17001_tf-g1
17002_tf-g2
2507_cloudship
3010_jsbsim_quadrotor_x
3011_jsbsim_hexarotor_x
6001_x4
6011_typhoon_h480
6011_typhoon_h480.post
4001_ign_x500
6001_ign_x4
6011_gazebo_typhoon_h480
6011_gazebo_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
10042_sihsim_xvert
17001_flightgear_tf-g1
17002_flightgear_tf-g2
)
@@ -6,6 +6,8 @@ param set-default IMU_INTEG_RATE 250
if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0" ]; then
echo "INFO [init] SIH simulator"
if ! simulator_sih start; then
echo "ERROR [init] simulator_sih failed to start"
exit 1
@@ -13,6 +15,8 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0"
elif [ "$PX4_SIMULATOR" = "ignition" ]; then
echo "INFO [init] Ignition Gazebo simulator"
# source generated gazebo_env.sh for IGN_GAZEBO_RESOURCE_PATH
if [ -f gazebo_env.sh ]; then
. ./gazebo_env.sh
@@ -34,7 +38,7 @@ elif [ "$PX4_SIMULATOR" = "ignition" ]; then
echo "INFO [init] ign gazebo already running"
fi
if simulator_ignition_bridge start -m "${PX4_SIM_MODEL}" -w "${PX4_SIM_WORLD}"; then
if simulator_ignition_bridge start -m "${PX4_SIM_MODEL#*ign_}" -w "${PX4_SIM_WORLD}"; then
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
@@ -43,6 +47,19 @@ elif [ "$PX4_SIMULATOR" = "ignition" ]; then
exit 1
fi
elif [ "$PX4_SIM_MODEL" = "jmavsim_iris" ] || [ "$PX4_SIMULATOR" = "jmavsim" ]; then
echo "INFO [init] jMAVSim simulator"
if jps | grep -i jmavsim; then
kill $(jps | grep -i jmavsim | awk '{print $1}') || true
sleep 1
fi
./jmavsim_run.sh -l -r 250 &
simulator_mavlink start -h localhost $((4560+px4_instance))
else
# otherwise start simulator (mavlink) module
simulator_tcp_port=$((4560+px4_instance))
@@ -53,15 +70,15 @@ else
if [ -z "${PX4_SIM_HOSTNAME}" ]; then
if [ -z "${PX4_SIM_HOST_ADDR}" ]; then
echo "PX4 SIM HOST: localhost"
echo "INFO [init] PX4_SIM_HOSTNAME: localhost"
simulator_mavlink start -c $simulator_tcp_port
else
echo "PX4 SIM HOST: $PX4_SIM_HOST_ADDR"
echo "INFO [init] PX4_SIM_HOSTNAME: $PX4_SIM_HOST_ADDR"
simulator_mavlink start -t $PX4_SIM_HOST_ADDR $simulator_tcp_port
fi
else
echo "PX4 SIM HOST: $PX4_SIM_HOSTNAME"
echo "INFO [init] PX4_SIM_HOSTNAME: $PX4_SIM_HOSTNAME"
simulator_mavlink start -h $PX4_SIM_HOSTNAME $simulator_tcp_port
fi
+1 -1
View File
@@ -1,6 +1,6 @@
#!/bin/sh
set -e
#set -e
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
+1 -1
View File
@@ -22,7 +22,7 @@ echo build_path: $build_path
rootfs="$build_path/rootfs" # this is the working directory
mkdir -p "$rootfs"
export PX4_SIM_MODEL=${model}
export PX4_SIM_MODEL=flightgear_${model}
echo "FG setup"
cd "${src_path}/Tools/simulation/flightgear/flightgear_bridge/"
+3 -3
View File
@@ -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))
+1 -5
View File
@@ -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}"
+3 -2
View File
@@ -2,7 +2,8 @@
set -e
SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
SCRIPT_DIR=$(dirname $(readlink -f "$BASH_SOURCE"))
cd "$SCRIPT_DIR/jMAVSim"
port=4560
@@ -73,4 +74,4 @@ fi
ant create_run_jar copy_res
cd out/production
java -XX:GCTimeRatio=20 -Djava.ext.dirs= -jar jmavsim_run.jar $device $extra_args
java -XX:GCTimeRatio=20 --illegal-access=permit -Djava.ext.dirs= -jar jmavsim_run.jar $device $extra_args
-67
View File
@@ -1,67 +0,0 @@
#!/usr/bin/env bash
set -e
if [ "$#" -lt 3 ]; then
echo usage: sitl_run.sh sitl_bin debugger src_path build_path
exit 1
fi
sitl_bin="$1"
debugger="$2"
src_path="$3"
build_path="$4"
echo SITL ARGS
echo sitl_bin: $sitl_bin
echo debugger: $debugger
echo src_path: $src_path
echo build_path: $build_path
rootfs="$build_path/rootfs" # this is the working directory
mkdir -p "$rootfs"
# To disable user input
if [[ -n "$NO_PXH" ]]; then
no_pxh=-d
else
no_pxh=""
fi
jmavsim_pid=`ps aux | grep java | grep "\-jar jmavsim_run.jar" | awk '{ print $2 }'`
if [ -n "$jmavsim_pid" ]; then
kill $jmavsim_pid
fi
export PX4_SIM_MODEL="iris"
# Start Java simulator
"$src_path"/Tools/simulation/jmavsim/jmavsim_run.sh -r 250 -l &
SIM_PID=$!
pushd "$rootfs" >/dev/null
# Do not exit on failure now from here on because we want the complete cleanup
set +e
sitl_command="\"$sitl_bin\" $no_pxh \"$build_path\"/etc"
echo SITL COMMAND: $sitl_command
if [ "$debugger" == "lldb" ]; then
eval lldb -- $sitl_command
elif [ "$debugger" == "gdb" ]; then
eval gdb --args $sitl_command
elif [ "$debugger" == "valgrind" ]; then
eval valgrind --track-origins=yes --leak-check=full -v $sitl_command
elif [ "$debugger" == "callgrind" ]; then
eval valgrind --tool=callgrind -v $sitl_command
else
eval $sitl_command
fi
popd >/dev/null
pkill -9 -P $SIM_PID
kill -9 $SIM_PID
+1 -1
View File
@@ -37,7 +37,7 @@ else
no_pxh=""
fi
export PX4_SIM_MODEL=${model}
export PX4_SIM_MODEL=jsbsim_${model}
export PX4_SIM_WORLD=${world}
# This is needed for aircraft namespace mapping
+1 -1
View File
@@ -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
-2
View File
@@ -1,5 +1,3 @@
set(config_sitl_viewer jmavsim CACHE STRING "viewer for sitl")
set_property(CACHE config_sitl_viewer PROPERTY STRINGS "jmavsim;none")
# If the environment variable 'replay' is defined, we are building with replay
# support. In this case, we enable the orb publisher rules.
+1 -1
View File
@@ -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"/>
+1 -1
View File
@@ -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)">
+1 -1
View File
@@ -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"/>
+1 -1
View File
@@ -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 -->
@@ -14,7 +14,7 @@
"environment": [
{
"name": "PX4_SIM_MODEL",
"value": "quadx"
"value": "sih_quadx"
}
],
"externalConsole": false,
@@ -58,7 +58,7 @@
"environment": [
{
"name": "PX4_SIM_MODEL",
"value": "${input:PX4_SIM_MODEL}"
"value": "gazebo_${input:PX4_SIM_MODEL}"
}
],
"externalConsole": false,
@@ -103,10 +103,9 @@
"environment": [
{
"name": "PX4_SIM_MODEL",
"value": "iris"
"value": "jmavsim_iris"
}
],
"preLaunchTask": "jmavsim",
"postDebugTask": "jmavsim kill",
"linux": {
"MIMode": "gdb",
@@ -15,7 +15,7 @@
"environment": [
{
"name": "PX4_SIM_MODEL",
"value": "${input:PX4_SIM_MODEL}"
"value": "ign_${input:PX4_SIM_MODEL}"
}
],
"externalConsole": false,
+23 -12
View File
@@ -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,22 +345,33 @@ int main(int argc, char **argv)
ret = run_startup_script(commands_file, absolute_binary_path, instance);
if (ret == 0) {
// We now block here until we need to exit.
if (pxh_off) {
wait_to_exit();
} else {
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;
}
// We now block here until we need to exit.
if (pxh_off) {
wait_to_exit();
} else {
px4_daemon::Pxh pxh;
pxh.run_pxh();
}
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);
}
@@ -72,21 +72,74 @@ file(GLOB ign_worlds
${PX4_SOURCE_DIR}/Tools/simulation/ignition/worlds/*.sdf
)
# find corresponding airframes
file(GLOB ign_airframes
RELATIVE ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes
${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_ign_*
)
# remove any .post files
foreach(ign_airframe IN LISTS ign_airframes)
if(ign_airframe MATCHES ".post")
list(REMOVE_ITEM ign_airframes ${ign_airframe})
endif()
endforeach()
list(REMOVE_DUPLICATES ign_airframes)
foreach(ign_airframe IN LISTS ign_airframes)
set(model_only)
string(REGEX REPLACE ".*_ign_" "" model_only ${ign_airframe})
if(EXISTS "${PX4_SOURCE_DIR}/Tools/simulation/ignition/models/${model_only}")
if((EXISTS "${PX4_SOURCE_DIR}/Tools/simulation/ignition/models/${model_only}/model.sdf"))
#message(STATUS "Ignition SDF file found for ${model_only}")
else()
message(WARNING "Ignition no SDF file found for ${model_only}")
endif()
else()
message(WARNING "model directory ${PX4_SOURCE_DIR}/Tools/simulation/ignition/models/${model_only} not found")
endif()
endforeach()
foreach(model ${ign_models})
# match model to airframe
set(airframe_model_only)
set(airframe_sys_autostart)
set(ign_airframe_found)
foreach(ign_airframe IN LISTS ign_airframes)
string(REGEX REPLACE ".*_ign_" "" airframe_model_only ${ign_airframe})
string(REGEX REPLACE "_ign_.*" "" airframe_sys_autostart ${ign_airframe})
if(model STREQUAL ${airframe_model_only})
set(ign_airframe_found ${ign_airframe})
break()
endif()
endforeach()
if(ign_airframe_found)
#message(STATUS "ign model: ${model} (${airframe_model_only}), airframe: ${ign_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
else()
message(WARNING "ign missing model: ${model} (${airframe_model_only}), airframe: ${ign_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
endif()
foreach(world ${ign_worlds})
get_filename_component("world_name" ${world} NAME_WE)
if(world_name MATCHES "default")
add_custom_target(ign_${model}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=${model} $<TARGET_FILE:px4>
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=ign_${model} $<TARGET_FILE:px4>
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4
)
else()
add_custom_target(ign_${model}_${world_name}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=${model} PX4_SIM_WORLD=${world_name} $<TARGET_FILE:px4>
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=ign_${model} PX4_SIM_WORLD=${world_name} $<TARGET_FILE:px4>
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4
@@ -95,7 +148,5 @@ foreach(model ${ign_models})
endforeach()
endforeach()
# TODO: PX4_IGN_MODELS_PATH
# PX4_IGN_WORLDS_PATH
# PX4_IGN_GAZEBO_MODELS, PX4_IGN_GAZEBO_WORLDS, IGN_GAZEBO_RESOURCE_PATH
configure_file(gazebo_env.sh.in ${PX4_BINARY_DIR}/rootfs/gazebo_env.sh)
@@ -24,6 +24,20 @@ if(ENABLE_LOCKSTEP_SCHEDULER STREQUAL "no")
tf-r1
)
# find corresponding airframes
file(GLOB flightgear_airframes
RELATIVE ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes
${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_flightgear_*
)
# remove any .post files
foreach(flightgear_airframe IN LISTS flightgear_airframes)
if(flightgear_airframe MATCHES ".post")
list(REMOVE_ITEM flightgear_airframes ${flightgear_airframe})
endif()
endforeach()
list(REMOVE_DUPLICATES flightgear_airframes)
# default flightgear target
add_custom_target(flightgear
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/flightgear/sitl_run.sh $<TARGET_FILE:px4> "rascal" ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
@@ -33,6 +47,28 @@ if(ENABLE_LOCKSTEP_SCHEDULER STREQUAL "no")
)
foreach(model ${models})
# match model to airframe
set(airframe_model_only)
set(airframe_sys_autostart)
set(flightgear_airframe_found)
foreach(flightgear_airframe IN LISTS flightgear_airframes)
string(REGEX REPLACE ".*_flightgear_" "" airframe_model_only ${flightgear_airframe})
string(REGEX REPLACE "_flightgear_.*" "" airframe_sys_autostart ${flightgear_airframe})
if(model STREQUAL ${airframe_model_only})
set(flightgear_airframe_found ${flightgear_airframe})
break()
endif()
endforeach()
if(flightgear_airframe_found)
#message(STATUS "flightgear model: ${model} (${airframe_model_only}), airframe: ${flightgear_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
else()
message(WARNING "flightgear missing model: ${model} (${airframe_model_only}), airframe: ${flightgear_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
endif()
add_custom_target(flightgear_${model}
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/flightgear/sitl_run.sh $<TARGET_FILE:px4> ${model} ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
@@ -62,7 +62,6 @@ set(debuggers
)
set(models
none
believer
boat
cloudship
@@ -76,7 +75,6 @@ set(models
iris_opt_flow_mockup
iris_rplidar
iris_vision
nxp_cupcar
omnicopter
plane
plane_cam
@@ -85,7 +83,6 @@ set(models
px4vision
r1_rover
rover
shell
standard_vtol
standard_vtol_drop
tailsitter
@@ -108,8 +105,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")
@@ -1,25 +1,33 @@
px4_add_git_submodule(TARGET git_jmavsim PATH "${PX4_SOURCE_DIR}/Tools/simulation/jmavsim/jMAVSim")
# create targets for each viewer/model/debugger combination
set(debuggers
none
gdb
lldb
valgrind
callgrind
)
find_program(JAVA_ANT_PATH "ant")
find_package(Java)
foreach(debugger ${debuggers})
if(debugger STREQUAL "none")
set(_targ_name "jmavsim")
else()
set(_targ_name "jmavsim_${debugger}")
endif()
if(JAVA_ANT_PATH AND Java_JAVAC_EXECUTABLE AND Java_JAVA_EXECUTABLE)
add_custom_target(${_targ_name}
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/jmavsim/sitl_run.sh $<TARGET_FILE:px4> ${debugger} ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
px4_add_git_submodule(TARGET git_jmavsim PATH "${PX4_SOURCE_DIR}/Tools/simulation/jmavsim/jMAVSim")
add_custom_target(jmavsim_run_symlink ALL
COMMAND ${CMAKE_COMMAND} -E create_symlink ${PX4_SOURCE_DIR}/Tools/simulation/jmavsim/jmavsim_run.sh ${PX4_BINARY_DIR}/rootfs/jmavsim_run.sh
BYPRODUCTS ${PX4_BINARY_DIR}/rootfs/jmavsim_run.sh
)
# build_jmavsim
add_custom_command(
OUTPUT ${PX4_SOURCE_DIR}/Tools/simulation/jmavsim/jMAVSim/out/production/jmavsim_run.jar
COMMAND ${JAVA_ANT_PATH} create_run_jar copy_res
WORKING_DIRECTORY ${PX4_SOURCE_DIR}/Tools/simulation/jmavsim/jMAVSim/
USES_TERMINAL
DEPENDS git_jmavsim jmavsim_run_symlink
COMMENT "building jMAVSim"
)
add_custom_target(build_jmavsim DEPENDS ${PX4_SOURCE_DIR}/Tools/simulation/jmavsim/jMAVSim/out/production/jmavsim_run.jar)
# launch helper
add_custom_target(jmavsim_iris
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=jmavsim_iris PX4_SIMULATOR=jmavsim $<TARGET_FILE:px4>
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 git_jmavsim
DEPENDS px4 git_jmavsim build_jmavsim jmavsim_run_symlink
)
endforeach()
endif()
@@ -1,56 +1,113 @@
px4_add_git_submodule(TARGET git_jsbsim_bridge PATH "${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/jsbsim_bridge")
include(ExternalProject)
ExternalProject_Add(jsbsim_bridge
SOURCE_DIR ${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/jsbsim_bridge
CMAKE_ARGS -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
BINARY_DIR ${PX4_BINARY_DIR}/build_jsbsim_bridge
INSTALL_COMMAND ""
DEPENDS git_jsbsim_bridge
USES_TERMINAL_CONFIGURE true
USES_TERMINAL_BUILD true
EXCLUDE_FROM_ALL true
BUILD_ALWAYS 1
if(DEFINED ENV{JSBSIM_ROOT_DIR} )
set(JSBSIM_ROOT_DIR "$ENV{JSBSIM_ROOT_DIR}" )
endif()
find_path(JSBSIM_INCLUDE_DIR
NAMES
FGFDMExec.h
PATHS
${JSBSIM_ROOT_DIR}/include/JSBSim
/usr/include/JSBSim
/usr/local/include/JSBSim
)
# jsbsim: create targets for jsbsim
set(models
rascal
quadrotor_x
hexarotor_x
malolo
)
if(JSBSIM_INCLUDE_DIR)
set(worlds
none
LSZH
)
px4_add_git_submodule(TARGET git_jsbsim_bridge PATH "${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/jsbsim_bridge")
# default jsbsim target
add_custom_target(jsbsim
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/sitl_run.sh $<TARGET_FILE:px4> "rascal" "LSZH" ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 jsbsim_bridge
)
include(ExternalProject)
ExternalProject_Add(jsbsim_bridge
SOURCE_DIR ${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/jsbsim_bridge
CMAKE_ARGS -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
BINARY_DIR ${PX4_BINARY_DIR}/build_jsbsim_bridge
INSTALL_COMMAND ""
DEPENDS git_jsbsim_bridge
USES_TERMINAL_CONFIGURE true
USES_TERMINAL_BUILD true
EXCLUDE_FROM_ALL true
BUILD_ALWAYS 1
)
foreach(model ${models})
foreach(world ${worlds})
if(world STREQUAL "none")
add_custom_target(jsbsim_${model}
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/sitl_run.sh $<TARGET_FILE:px4> ${model} "LSZH" ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 jsbsim_bridge
)
else()
add_custom_target(jsbsim_${model}__${world}
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/sitl_run.sh $<TARGET_FILE:px4> ${model} ${world} ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 jsbsim_bridge
)
# jsbsim: create targets for jsbsim
set(models
rascal
quadrotor_x
hexarotor_x
malolo
)
set(worlds
none
LSZH
)
# find corresponding airframes
file(GLOB jsbsim_airframes
RELATIVE ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes
${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_jsbsim_*
)
# remove any .post files
foreach(jsbsim_airframe IN LISTS jsbsim_airframes)
if(jsbsim_airframe MATCHES ".post")
list(REMOVE_ITEM jsbsim_airframes ${jsbsim_airframe})
endif()
endforeach()
endforeach()
list(REMOVE_DUPLICATES jsbsim_airframes)
# default jsbsim target
add_custom_target(jsbsim
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/sitl_run.sh $<TARGET_FILE:px4> "rascal" "LSZH" ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 jsbsim_bridge
)
foreach(model ${models})
# match model to airframe
set(airframe_model_only)
set(airframe_sys_autostart)
set(jsbsim_airframe_found)
foreach(jsbsim_airframe IN LISTS jsbsim_airframes)
string(REGEX REPLACE ".*_jsbsim_" "" airframe_model_only ${jsbsim_airframe})
string(REGEX REPLACE "_jsbsim_.*" "" airframe_sys_autostart ${jsbsim_airframe})
if(model STREQUAL ${airframe_model_only})
set(jsbsim_airframe_found ${jsbsim_airframe})
break()
endif()
endforeach()
if(jsbsim_airframe_found)
#message(STATUS "jsbsim model: ${model} (${airframe_model_only}), airframe: ${jsbsim_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
else()
message(WARNING "jsbsim missing model: ${model} (${airframe_model_only}), airframe: ${jsbsim_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
endif()
foreach(world ${worlds})
if(world STREQUAL "none")
add_custom_target(jsbsim_${model}
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/sitl_run.sh $<TARGET_FILE:px4> ${model} "LSZH" ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 jsbsim_bridge
)
else()
add_custom_target(jsbsim_${model}__${world}
COMMAND ${PX4_SOURCE_DIR}/Tools/simulation/jsbsim/sitl_run.sh $<TARGET_FILE:px4> ${model} ${world} ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 jsbsim_bridge
)
endif()
endforeach()
endforeach()
endif()
@@ -55,9 +55,45 @@ if(PX4_PLATFORM MATCHES "posix")
xvert
)
# find corresponding airframes
file(GLOB sihsim_airframes
RELATIVE ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes
${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_sihsim_*
)
# remove any .post files
foreach(sihsim_airframe IN LISTS sihsim_airframes)
if(sihsim_airframe MATCHES ".post")
list(REMOVE_ITEM sihsim_airframes ${sihsim_airframe})
endif()
endforeach()
list(REMOVE_DUPLICATES sihsim_airframes)
foreach(model ${models})
# match model to airframe
set(airframe_model_only)
set(airframe_sys_autostart)
set(sihsim_airframe_found)
foreach(sihsim_airframe IN LISTS sihsim_airframes)
string(REGEX REPLACE ".*_sihsim_" "" airframe_model_only ${sihsim_airframe})
string(REGEX REPLACE "_sihsim_.*" "" airframe_sys_autostart ${sihsim_airframe})
if(model STREQUAL ${airframe_model_only})
set(sihsim_airframe_found ${sihsim_airframe})
break()
endif()
endforeach()
if(sihsim_airframe_found)
#message(STATUS "sihsim model: ${model} (${airframe_model_only}), airframe: ${sihsim_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
else()
message(WARNING "sihsim missing model: ${model} (${airframe_model_only}), airframe: ${sihsim_airframe_found}, SYS_AUTOSTART: ${airframe_sys_autostart}")
endif()
add_custom_target(sihsim_${model}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=${model} PX4_SIMULATOR=sihsim $<TARGET_FILE:px4>
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=sihsim_${model} PX4_SIMULATOR=sihsim $<TARGET_FILE:px4>
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4
-7
View File
@@ -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")