mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-04 02:20:05 +08:00
Compare commits
2 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| fcc0c79c01 | |||
| 86706ce218 |
@@ -81,7 +81,7 @@ jobs:
|
||||
env:
|
||||
PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}}
|
||||
DONT_RUN: 1
|
||||
run: make px4_sitl_default sitl_gazebo mavsdk_tests
|
||||
run: make px4_sitl_default gazebo mavsdk_tests
|
||||
- name: ccache post-run mavsdk_tests
|
||||
run: ccache -s
|
||||
|
||||
|
||||
Vendored
+39
@@ -49,6 +49,45 @@
|
||||
"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",
|
||||
|
||||
+1
-4
@@ -296,10 +296,7 @@ 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(coverage)
|
||||
include(sanitizers)
|
||||
|
||||
# Define GNU standard installation directories
|
||||
|
||||
@@ -129,59 +129,57 @@ else
|
||||
BUILD_DIR_SUFFIX :=
|
||||
endif
|
||||
|
||||
CMAKE_ARGS ?=
|
||||
|
||||
# additional config parameters passed to cmake
|
||||
ifdef EXTERNAL_MODULES_LOCATION
|
||||
override CMAKE_ARGS += -DEXTERNAL_MODULES_LOCATION:STRING=$(EXTERNAL_MODULES_LOCATION)
|
||||
CMAKE_ARGS += -DEXTERNAL_MODULES_LOCATION:STRING=$(EXTERNAL_MODULES_LOCATION)
|
||||
endif
|
||||
|
||||
ifdef PX4_CMAKE_BUILD_TYPE
|
||||
override CMAKE_ARGS += -DCMAKE_BUILD_TYPE=${PX4_CMAKE_BUILD_TYPE}
|
||||
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=${PX4_CMAKE_BUILD_TYPE}
|
||||
else
|
||||
|
||||
# Address Sanitizer
|
||||
ifdef PX4_ASAN
|
||||
override CMAKE_ARGS += -DCMAKE_BUILD_TYPE=AddressSanitizer
|
||||
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=AddressSanitizer
|
||||
endif
|
||||
|
||||
# Memory Sanitizer
|
||||
ifdef PX4_MSAN
|
||||
override CMAKE_ARGS += -DCMAKE_BUILD_TYPE=MemorySanitizer
|
||||
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=MemorySanitizer
|
||||
endif
|
||||
|
||||
# Thread Sanitizer
|
||||
ifdef PX4_TSAN
|
||||
override CMAKE_ARGS += -DCMAKE_BUILD_TYPE=ThreadSanitizer
|
||||
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=ThreadSanitizer
|
||||
endif
|
||||
|
||||
# Undefined Behavior Sanitizer
|
||||
ifdef PX4_UBSAN
|
||||
override CMAKE_ARGS += -DCMAKE_BUILD_TYPE=UndefinedBehaviorSanitizer
|
||||
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=UndefinedBehaviorSanitizer
|
||||
endif
|
||||
|
||||
# Fuzz Testing
|
||||
ifdef PX4_FUZZ
|
||||
override CMAKE_ARGS += -DCMAKE_BUILD_TYPE=FuzzTesting
|
||||
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=FuzzTesting
|
||||
endif
|
||||
|
||||
endif
|
||||
|
||||
# Pick up specific Python path if set
|
||||
ifdef PYTHON_EXECUTABLE
|
||||
override CMAKE_ARGS += -DPYTHON_EXECUTABLE=${PYTHON_EXECUTABLE}
|
||||
CMAKE_ARGS += -DPYTHON_EXECUTABLE=${PYTHON_EXECUTABLE}
|
||||
endif
|
||||
|
||||
# Check if the microRTPS agent is to be built
|
||||
ifdef BUILD_MICRORTPS_AGENT
|
||||
override CMAKE_ARGS += -DBUILD_MICRORTPS_AGENT=ON
|
||||
CMAKE_ARGS += -DBUILD_MICRORTPS_AGENT=ON
|
||||
endif
|
||||
|
||||
# Functions
|
||||
# --------------------------------------------------------------------
|
||||
# describe how to build a cmake config
|
||||
define cmake-build
|
||||
$(eval override CMAKE_ARGS += -DCONFIG=$(1))
|
||||
$(eval CMAKE_ARGS += -DCONFIG=$(1))
|
||||
@$(eval BUILD_DIR = "$(SRC_DIR)/build/$(1)")
|
||||
@# check if the desired cmake configuration matches the cache then CMAKE_CACHE_CHECK stays empty
|
||||
@$(call cmake-cache-check)
|
||||
@@ -385,7 +383,7 @@ format:
|
||||
.PHONY: rostest python_coverage
|
||||
|
||||
tests:
|
||||
$(eval override CMAKE_ARGS += -DTESTFILTER=$(TESTFILTER))
|
||||
$(eval CMAKE_ARGS += -DTESTFILTER=$(TESTFILTER))
|
||||
$(eval ARGS += test_results)
|
||||
$(eval ASAN_OPTIONS += color=always:check_initialization_order=1:detect_stack_use_after_return=1)
|
||||
$(eval UBSAN_OPTIONS += color=always)
|
||||
|
||||
@@ -1,34 +0,0 @@
|
||||
#!/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
|
||||
|
||||
@@ -1,33 +0,0 @@
|
||||
#!/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
|
||||
|
||||
@@ -0,0 +1,11 @@
|
||||
#!/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
|
||||
|
||||
+1
@@ -41,3 +41,4 @@ param set-default PWM_MAIN_FUNC3 103
|
||||
param set-default PWM_MAIN_FUNC4 104
|
||||
|
||||
param set SIH_VEHICLE_TYPE 0
|
||||
|
||||
@@ -1,47 +0,0 @@
|
||||
#!/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
|
||||
@@ -0,0 +1,25 @@
|
||||
#!/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
|
||||
@@ -1,38 +0,0 @@
|
||||
#!/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
|
||||
@@ -0,0 +1,16 @@
|
||||
#!/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
|
||||
@@ -1,33 +0,0 @@
|
||||
#!/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
|
||||
|
||||
@@ -0,0 +1,11 @@
|
||||
#!/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
|
||||
|
||||
@@ -1,42 +0,0 @@
|
||||
#!/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
|
||||
|
||||
@@ -0,0 +1,20 @@
|
||||
#!/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
|
||||
|
||||
@@ -1,34 +0,0 @@
|
||||
#!/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
|
||||
|
||||
@@ -0,0 +1,12 @@
|
||||
#!/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
|
||||
|
||||
@@ -1,40 +0,0 @@
|
||||
#!/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
|
||||
@@ -0,0 +1,18 @@
|
||||
#!/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
|
||||
@@ -0,0 +1,13 @@
|
||||
#!/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
|
||||
@@ -1,33 +0,0 @@
|
||||
#!/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
|
||||
@@ -0,0 +1,11 @@
|
||||
#!/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
|
||||
@@ -1,81 +0,0 @@
|
||||
#!/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
|
||||
@@ -0,0 +1,12 @@
|
||||
#!/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,9 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with catapult
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/1030_plane
|
||||
|
||||
param set-default RWTO_TKOFF 0
|
||||
|
||||
+1
@@ -63,3 +63,4 @@ 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
|
||||
|
||||
@@ -1,78 +0,0 @@
|
||||
#!/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
|
||||
@@ -0,0 +1,9 @@
|
||||
#!/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
|
||||
+1
-4
@@ -1,6 +1,6 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with catapult
|
||||
# @name Plane SITL
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
@@ -73,6 +73,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
|
||||
|
||||
param set-default RWTO_TKOFF 0
|
||||
|
||||
@@ -1,65 +0,0 @@
|
||||
#!/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
|
||||
@@ -1,93 +0,0 @@
|
||||
#!/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
|
||||
|
||||
@@ -0,0 +1,18 @@
|
||||
#!/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
|
||||
|
||||
@@ -1,78 +0,0 @@
|
||||
#!/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
|
||||
@@ -0,0 +1,9 @@
|
||||
#!/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,58 +32,55 @@
|
||||
############################################################################
|
||||
|
||||
px4_add_romfs_files(
|
||||
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
|
||||
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
|
||||
1039_advanced_plane
|
||||
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
|
||||
|
||||
2507_gazebo_cloudship
|
||||
4001_x500
|
||||
|
||||
3010_jsbsim_quadrotor_x
|
||||
3011_jsbsim_hexarotor_x
|
||||
17001_tf-g1
|
||||
17002_tf-g2
|
||||
2507_cloudship
|
||||
|
||||
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
|
||||
6001_x4
|
||||
6011_typhoon_h480
|
||||
6011_typhoon_h480.post
|
||||
)
|
||||
|
||||
@@ -6,8 +6,6 @@ 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
|
||||
@@ -15,8 +13,6 @@ 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
|
||||
@@ -38,7 +34,7 @@ elif [ "$PX4_SIMULATOR" = "ignition" ]; then
|
||||
echo "INFO [init] ign gazebo already running"
|
||||
fi
|
||||
|
||||
if simulator_ignition_bridge start -m "${PX4_SIM_MODEL#*ign_}" -w "${PX4_SIM_WORLD}"; then
|
||||
if simulator_ignition_bridge start -m "${PX4_SIM_MODEL}" -w "${PX4_SIM_WORLD}"; then
|
||||
sensor_baro_sim start
|
||||
sensor_gps_sim start
|
||||
sensor_mag_sim start
|
||||
@@ -47,19 +43,6 @@ 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))
|
||||
@@ -70,15 +53,15 @@ else
|
||||
if [ -z "${PX4_SIM_HOSTNAME}" ]; then
|
||||
|
||||
if [ -z "${PX4_SIM_HOST_ADDR}" ]; then
|
||||
echo "INFO [init] PX4_SIM_HOSTNAME: localhost"
|
||||
echo "PX4 SIM HOST: localhost"
|
||||
simulator_mavlink start -c $simulator_tcp_port
|
||||
else
|
||||
echo "INFO [init] PX4_SIM_HOSTNAME: $PX4_SIM_HOST_ADDR"
|
||||
echo "PX4 SIM HOST: $PX4_SIM_HOST_ADDR"
|
||||
simulator_mavlink start -t $PX4_SIM_HOST_ADDR $simulator_tcp_port
|
||||
fi
|
||||
|
||||
else
|
||||
echo "INFO [init] PX4_SIM_HOSTNAME: $PX4_SIM_HOSTNAME"
|
||||
echo "PX4 SIM HOST: $PX4_SIM_HOSTNAME"
|
||||
simulator_mavlink start -h $PX4_SIM_HOSTNAME $simulator_tcp_port
|
||||
fi
|
||||
|
||||
|
||||
@@ -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)
|
||||
|
||||
@@ -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=flightgear_${model}
|
||||
export PX4_SIM_MODEL=${model}
|
||||
|
||||
echo "FG setup"
|
||||
cd "${src_path}/Tools/simulation/flightgear/flightgear_bridge/"
|
||||
|
||||
Submodule Tools/simulation/gazebo/sitl_gazebo updated: 07552959bc...40d340931c
@@ -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 sitl_gazebo'
|
||||
# It assumes px4 is already built, with 'make px4_sitl_default 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=gazebo_${vehicle_model}
|
||||
export PX4_SIM_MODEL=${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=gazebo_${target_vehicle}
|
||||
export PX4_SIM_MODEL=${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=gazebo_${model}
|
||||
export PX4_SIM_MODEL=${model}
|
||||
export PX4_SIM_WORLD=${world}
|
||||
|
||||
SIM_PID=0
|
||||
@@ -75,6 +75,10 @@ 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}"
|
||||
|
||||
@@ -2,8 +2,7 @@
|
||||
|
||||
set -e
|
||||
|
||||
SCRIPT_DIR=$(dirname $(readlink -f "$BASH_SOURCE"))
|
||||
|
||||
SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
|
||||
cd "$SCRIPT_DIR/jMAVSim"
|
||||
|
||||
port=4560
|
||||
@@ -74,4 +73,4 @@ fi
|
||||
ant create_run_jar copy_res
|
||||
cd out/production
|
||||
|
||||
java -XX:GCTimeRatio=20 --illegal-access=permit -Djava.ext.dirs= -jar jmavsim_run.jar $device $extra_args
|
||||
java -XX:GCTimeRatio=20 -Djava.ext.dirs= -jar jmavsim_run.jar $device $extra_args
|
||||
|
||||
Executable
+67
@@ -0,0 +1,67 @@
|
||||
#!/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
|
||||
@@ -37,7 +37,7 @@ else
|
||||
no_pxh=""
|
||||
fi
|
||||
|
||||
export PX4_SIM_MODEL=jsbsim_${model}
|
||||
export PX4_SIM_MODEL=${model}
|
||||
export PX4_SIM_WORLD=${world}
|
||||
|
||||
# This is needed for aircraft namespace mapping
|
||||
|
||||
@@ -19,7 +19,7 @@ pkill -x px4 || true
|
||||
|
||||
sleep 1
|
||||
|
||||
export PX4_SIM_MODEL=gazebo_iris
|
||||
export PX4_SIM_MODEL=iris
|
||||
|
||||
n=0
|
||||
while [ $n -lt $sitl_num ]; do
|
||||
|
||||
@@ -166,10 +166,6 @@
|
||||
GPIO_nVDD_5V_PERIPH_EN, \
|
||||
GPIO_nVDD_5V_PERIPH_OC, \
|
||||
GPIO_nVDD_5V_HIPOWER_OC, \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C1_SCL), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C1_SDA), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SCL), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SDA), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
|
||||
|
||||
@@ -1,3 +1,5 @@
|
||||
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.
|
||||
|
||||
@@ -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="gazebo_$(arg vehicle)" />
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
|
||||
|
||||
<!-- gazebo configs -->
|
||||
<arg name="gui" default="true"/>
|
||||
|
||||
+1
-1
@@ -9,7 +9,7 @@
|
||||
<arg name="ID" default="0"/>
|
||||
<arg name="interactive" default="true"/>
|
||||
|
||||
<env name="PX4_SIM_MODEL" value="gazebo_$(arg vehicle)" />
|
||||
<env name="PX4_SIM_MODEL" value="$(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="gazebo_$(arg vehicle)" />
|
||||
<env name="PX4_SIM_MODEL" value="$(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="gazebo_$(arg vehicle)" />
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
|
||||
<arg name="mavlink_udp_port" default="14560"/>
|
||||
<arg name="mavlink_tcp_port" default="4560"/>
|
||||
<!-- PX4 configs -->
|
||||
|
||||
@@ -118,4 +118,5 @@ bool parachute_system_healthy
|
||||
bool avoidance_system_required # Set to true if avoidance system is enabled via COM_OBS_AVOID parameter
|
||||
bool avoidance_system_valid # Status of the obstacle avoidance system
|
||||
|
||||
bool battery_healthy # set if battery is available and not low
|
||||
|
||||
|
||||
@@ -7,7 +7,6 @@ uint64 timestamp # time since system start (microseconds)
|
||||
uint32 mode_req_angular_velocity
|
||||
uint32 mode_req_attitude
|
||||
uint32 mode_req_local_position
|
||||
uint32 mode_req_local_position_relaxed
|
||||
uint32 mode_req_global_position
|
||||
uint32 mode_req_local_alt
|
||||
uint32 mode_req_mission
|
||||
@@ -24,11 +23,18 @@ bool angular_velocity_valid
|
||||
bool attitude_valid
|
||||
bool local_altitude_valid
|
||||
bool local_position_valid # set to true by the commander app if the quality of the local position estimate is good enough to use for navigation
|
||||
bool local_position_valid_relaxed # Local position with reduced accuracy requirements (e.g. flying with optical flow)
|
||||
bool local_velocity_valid # set to true by the commander app if the quality of the local horizontal velocity data is good enough to use for navigation
|
||||
bool global_position_valid # set to true by the commander app if the quality of the global position estimate is good enough to use for navigation
|
||||
bool gps_position_valid
|
||||
bool home_position_valid # indicates a valid home position (a valid home position is not always a valid launch)
|
||||
bool escs_error # set to true if one or more ESCs reporting esc_status are offline
|
||||
bool escs_failure # set to true if one or more ESCs reporting esc_status has a failure
|
||||
|
||||
bool position_reliant_on_gps
|
||||
bool position_reliant_on_optical_flow
|
||||
bool position_reliant_on_vision_position
|
||||
|
||||
bool dead_reckoning
|
||||
|
||||
bool offboard_control_signal_lost
|
||||
|
||||
@@ -36,8 +42,3 @@ bool rc_signal_found_once
|
||||
bool rc_calibration_in_progress
|
||||
bool vtol_transition_failure # Set to true if vtol transition failed
|
||||
|
||||
bool battery_low_remaining_time
|
||||
bool battery_unhealthy
|
||||
|
||||
uint8 battery_warning
|
||||
|
||||
|
||||
@@ -117,6 +117,7 @@ __END_DECLS
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <stdint.h>
|
||||
#include <sys/cdefs.h>
|
||||
#include <stdio.h>
|
||||
#include <stdarg.h>
|
||||
|
||||
@@ -375,28 +376,15 @@ __END_DECLS
|
||||
/****************************************************************************
|
||||
* Messages that should never be filtered or compiled out
|
||||
****************************************************************************/
|
||||
#if defined(PRINTF_LOG)
|
||||
#define PX4_INFO(FMT, ...) printf(FMT "\n", ##__VA_ARGS__)
|
||||
#else
|
||||
#define PX4_INFO(FMT, ...) __px4_log_modulename(_PX4_LOG_LEVEL_INFO, FMT, ##__VA_ARGS__)
|
||||
#endif
|
||||
|
||||
#if defined(__NUTTX) || defined(PRINTF_LOG)
|
||||
#ifdef __NUTTX
|
||||
#define PX4_INFO_RAW printf
|
||||
#else
|
||||
#define PX4_INFO_RAW(FMT, ...) __px4_log_raw(_PX4_LOG_LEVEL_INFO, FMT, ##__VA_ARGS__)
|
||||
#endif
|
||||
|
||||
#if defined(PRINTF_LOG)
|
||||
/****************************************************************************
|
||||
* Direct printf output for minimized dependencies
|
||||
****************************************************************************/
|
||||
#define PX4_PANIC(FMT, ...) printf("Panic: " FMT "\n", ##__VA_ARGS__)
|
||||
#define PX4_ERR(FMT, ...) printf("Error: " FMT "\n", ##__VA_ARGS__)
|
||||
#define PX4_WARN(FMT, ...) printf("Warn: " FMT "\n", ##__VA_ARGS__)
|
||||
#define PX4_DEBUG(FMT, ...) printf(FMT "\n", ##__VA_ARGS__)
|
||||
|
||||
#elif defined(TRACE_BUILD)
|
||||
#if defined(TRACE_BUILD)
|
||||
/****************************************************************************
|
||||
* Extremely Verbose settings for a Trace build
|
||||
****************************************************************************/
|
||||
|
||||
@@ -14,7 +14,7 @@
|
||||
"environment": [
|
||||
{
|
||||
"name": "PX4_SIM_MODEL",
|
||||
"value": "sih_quadx"
|
||||
"value": "quadx"
|
||||
}
|
||||
],
|
||||
"externalConsole": false,
|
||||
@@ -58,7 +58,7 @@
|
||||
"environment": [
|
||||
{
|
||||
"name": "PX4_SIM_MODEL",
|
||||
"value": "gazebo_${input:PX4_SIM_MODEL}"
|
||||
"value": "${input:PX4_SIM_MODEL}"
|
||||
}
|
||||
],
|
||||
"externalConsole": false,
|
||||
@@ -103,9 +103,10 @@
|
||||
"environment": [
|
||||
{
|
||||
"name": "PX4_SIM_MODEL",
|
||||
"value": "jmavsim_iris"
|
||||
"value": "iris"
|
||||
}
|
||||
],
|
||||
"preLaunchTask": "jmavsim",
|
||||
"postDebugTask": "jmavsim kill",
|
||||
"linux": {
|
||||
"MIMode": "gdb",
|
||||
|
||||
@@ -15,7 +15,7 @@
|
||||
"environment": [
|
||||
{
|
||||
"name": "PX4_SIM_MODEL",
|
||||
"value": "ign_${input:PX4_SIM_MODEL}"
|
||||
"value": "${input:PX4_SIM_MODEL}"
|
||||
}
|
||||
],
|
||||
"externalConsole": false,
|
||||
@@ -54,10 +54,10 @@
|
||||
"id": "PX4_SIM_MODEL",
|
||||
"description": "PX4_SIM_MODEL",
|
||||
"options": [
|
||||
"x500",
|
||||
"x3",
|
||||
"x4"
|
||||
],
|
||||
"default": "x500"
|
||||
"default": "x3"
|
||||
}
|
||||
]
|
||||
}
|
||||
|
||||
@@ -37,7 +37,6 @@
|
||||
* High-resolution timer with callouts and timekeeping.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/atomic.h>
|
||||
#include <px4_platform_common/time.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <px4_platform_common/defines.h>
|
||||
@@ -53,7 +52,6 @@
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
#include <lockstep_scheduler/lockstep_scheduler.h>
|
||||
static LockstepScheduler lockstep_scheduler {};
|
||||
#endif
|
||||
|
||||
// Intervals in usec
|
||||
@@ -79,11 +77,22 @@ __EXPORT uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
|
||||
static px4_sem_t _hrt_lock;
|
||||
static struct work_s _hrt_work;
|
||||
|
||||
static hrt_abstime px4_timestart_monotonic = 0;
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
static LockstepScheduler *lockstep_scheduler = new LockstepScheduler();
|
||||
#endif
|
||||
|
||||
static void hrt_latency_update();
|
||||
|
||||
static void hrt_call_reschedule();
|
||||
static void hrt_call_invoke();
|
||||
|
||||
hrt_abstime hrt_absolute_time_offset()
|
||||
{
|
||||
return px4_timestart_monotonic;
|
||||
}
|
||||
|
||||
static void hrt_lock()
|
||||
{
|
||||
// loop as the wait may be interrupted by a signal
|
||||
@@ -127,8 +136,8 @@ hrt_abstime hrt_absolute_time()
|
||||
{
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
// optimized case (avoid ts_to_abstime) if lockstep scheduler is used
|
||||
return lockstep_scheduler.get_absolute_time();
|
||||
|
||||
const uint64_t abstime = lockstep_scheduler->get_absolute_time();
|
||||
return abstime - px4_timestart_monotonic;
|
||||
#else // defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
struct timespec ts;
|
||||
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
@@ -467,7 +476,8 @@ int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
|
||||
{
|
||||
if (clk_id == CLOCK_MONOTONIC) {
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
abstime_to_ts(tp, lockstep_scheduler.get_absolute_time());
|
||||
const uint64_t abstime = lockstep_scheduler->get_absolute_time();
|
||||
abstime_to_ts(tp, abstime - px4_timestart_monotonic);
|
||||
return 0;
|
||||
#else // defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
#if defined(__PX4_DARWIN)
|
||||
@@ -491,60 +501,71 @@ int px4_clock_settime(clockid_t clk_id, const struct timespec *ts)
|
||||
return system_clock_settime(clk_id, ts);
|
||||
|
||||
} else {
|
||||
lockstep_scheduler.set_absolute_time(ts_to_abstime(ts));
|
||||
const uint64_t time_us = ts_to_abstime(ts);
|
||||
|
||||
if (px4_timestart_monotonic == 0) {
|
||||
px4_timestart_monotonic = time_us;
|
||||
}
|
||||
|
||||
lockstep_scheduler->set_absolute_time(time_us);
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int px4_usleep(useconds_t usec)
|
||||
{
|
||||
if (lockstep_scheduler.get_absolute_time() == 0) {
|
||||
// Until the time is set by the simulator, we fallback to the normal usleep
|
||||
if (px4_timestart_monotonic == 0) {
|
||||
// Until the time is set by the simulator, we fallback to the normal
|
||||
// usleep;
|
||||
return system_usleep(usec);
|
||||
}
|
||||
|
||||
const uint64_t time_finished = lockstep_scheduler.get_absolute_time() + usec;
|
||||
const uint64_t time_finished = lockstep_scheduler->get_absolute_time() + usec;
|
||||
|
||||
return lockstep_scheduler.usleep_until(time_finished);
|
||||
return lockstep_scheduler->usleep_until(time_finished);
|
||||
}
|
||||
|
||||
unsigned int px4_sleep(unsigned int seconds)
|
||||
{
|
||||
if (lockstep_scheduler.get_absolute_time() == 0) {
|
||||
// Until the time is set by the simulator, we fallback to the normal sleep
|
||||
if (px4_timestart_monotonic == 0) {
|
||||
// Until the time is set by the simulator, we fallback to the normal
|
||||
// sleep;
|
||||
return system_sleep(seconds);
|
||||
}
|
||||
|
||||
const uint64_t time_finished = lockstep_scheduler.get_absolute_time() + ((uint64_t)seconds * 1000000);
|
||||
const uint64_t time_finished = lockstep_scheduler->get_absolute_time() +
|
||||
((uint64_t)seconds * 1000000);
|
||||
|
||||
return lockstep_scheduler.usleep_until(time_finished);
|
||||
return lockstep_scheduler->usleep_until(time_finished);
|
||||
}
|
||||
|
||||
int px4_pthread_cond_timedwait(pthread_cond_t *cond,
|
||||
pthread_mutex_t *mutex,
|
||||
const struct timespec *ts)
|
||||
{
|
||||
const uint64_t scheduled = ts_to_abstime(ts);
|
||||
return lockstep_scheduler.cond_timedwait(cond, mutex, scheduled);
|
||||
const uint64_t time_us = ts_to_abstime(ts);
|
||||
const uint64_t scheduled = time_us + px4_timestart_monotonic;
|
||||
return lockstep_scheduler->cond_timedwait(cond, mutex, scheduled);
|
||||
}
|
||||
|
||||
int px4_lockstep_register_component()
|
||||
{
|
||||
return lockstep_scheduler.components().register_component();
|
||||
return lockstep_scheduler->components().register_component();
|
||||
}
|
||||
|
||||
void px4_lockstep_unregister_component(int component)
|
||||
{
|
||||
lockstep_scheduler.components().unregister_component(component);
|
||||
lockstep_scheduler->components().unregister_component(component);
|
||||
}
|
||||
|
||||
void px4_lockstep_progress(int component)
|
||||
{
|
||||
lockstep_scheduler.components().lockstep_progress(component);
|
||||
lockstep_scheduler->components().lockstep_progress(component);
|
||||
}
|
||||
|
||||
void px4_lockstep_wait_for_components()
|
||||
{
|
||||
lockstep_scheduler.components().wait_for_components();
|
||||
lockstep_scheduler->components().wait_for_components();
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2015-2022 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2015-2018 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,33 +345,22 @@ 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;
|
||||
@@ -464,7 +453,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,8 +228,6 @@ Server::_server_main()
|
||||
_unlock();
|
||||
}
|
||||
|
||||
std::string sock_path = get_socket_path(_instance_id);
|
||||
unlink(sock_path.c_str());
|
||||
close(_fd);
|
||||
}
|
||||
|
||||
|
||||
@@ -235,6 +235,11 @@ __EXPORT extern void hrt_call_delay(struct hrt_call *entry, hrt_abstime delay);
|
||||
*/
|
||||
__EXPORT extern void hrt_init(void);
|
||||
|
||||
#ifdef __PX4_POSIX
|
||||
|
||||
__EXPORT extern hrt_abstime hrt_absolute_time_offset(void);
|
||||
|
||||
#endif
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
|
||||
__EXPORT extern int px4_lockstep_register_component(void);
|
||||
|
||||
@@ -49,7 +49,6 @@ AK09916::AK09916(const I2CSPIDriverConfig &config) :
|
||||
|
||||
AK09916::~AK09916()
|
||||
{
|
||||
perf_free(_reset_perf);
|
||||
perf_free(_transfer_perf);
|
||||
perf_free(_bad_register_perf);
|
||||
perf_free(_bad_transfer_perf);
|
||||
@@ -65,8 +64,6 @@ int AK09916::init()
|
||||
return ret;
|
||||
}
|
||||
|
||||
_retries = 2;
|
||||
|
||||
return Reset() ? 0 : -1;
|
||||
}
|
||||
|
||||
@@ -82,7 +79,6 @@ void AK09916::print_status()
|
||||
{
|
||||
I2CSPIDriverBase::print_status();
|
||||
|
||||
perf_print_counter(_reset_perf);
|
||||
perf_print_counter(_transfer_perf);
|
||||
perf_print_counter(_bad_register_perf);
|
||||
perf_print_counter(_bad_transfer_perf);
|
||||
@@ -112,7 +108,6 @@ void AK09916::RunImpl()
|
||||
{
|
||||
switch (_state) {
|
||||
case STATE::RESET:
|
||||
perf_count(_reset_perf);
|
||||
// CNTL3 SRST: Soft reset
|
||||
RegisterWrite(Register::CNTL3, CNTL3_BIT::SRST);
|
||||
_reset_timestamp = hrt_absolute_time();
|
||||
@@ -184,8 +179,6 @@ void AK09916::RunImpl()
|
||||
const int16_t z = combine(buffer.HZH, buffer.HZL);
|
||||
|
||||
// sensor's frame is +X forward (X), +Y right (Y), +Z down (Z)
|
||||
_px4_mag.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf)
|
||||
+ perf_event_count(_magnetic_sensor_overflow_perf));
|
||||
_px4_mag.update(timestamp_sample, x, y, z);
|
||||
|
||||
success = true;
|
||||
|
||||
@@ -97,7 +97,6 @@ private:
|
||||
|
||||
PX4Magnetometer _px4_mag;
|
||||
|
||||
perf_counter_t _reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": reset")};
|
||||
perf_counter_t _transfer_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": transfer")};
|
||||
perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")};
|
||||
perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")};
|
||||
|
||||
@@ -106,8 +106,8 @@
|
||||
"description": "Distance sensor"
|
||||
},
|
||||
"128": {
|
||||
"name": "remote_control",
|
||||
"description": "Remote Control (RC or Joystick)"
|
||||
"name": "manual_control_input",
|
||||
"description": "RC or virtual joystick input"
|
||||
},
|
||||
"256": {
|
||||
"name": "motors_escs",
|
||||
@@ -198,6 +198,10 @@
|
||||
"536870912": {
|
||||
"name": "gyro",
|
||||
"description": "Gyroscope"
|
||||
},
|
||||
"1073741824": {
|
||||
"name": "remote_control",
|
||||
"description": "Remote Control"
|
||||
}
|
||||
}
|
||||
},
|
||||
|
||||
+1
-1
Submodule src/lib/events/libevents updated: 82dabdb914...a8ca26efd6
@@ -23,7 +23,7 @@ enum class params : uint16_t {
|
||||
static constexpr param_info_s parameters[] = {
|
||||
{% for param in params %}
|
||||
{
|
||||
.name = "{{ param.attrib["name"] }}",
|
||||
"{{ param.attrib["name"] }}",
|
||||
{%- if param.attrib["type"] == "FLOAT" %}
|
||||
.val = {{ "{" }} .f = {{ param.attrib["default"] }} {{ "}" }},
|
||||
{%- elif param.attrib["type"] == "INT32" %}
|
||||
|
||||
@@ -41,6 +41,7 @@
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <sys/queue.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <math.h>
|
||||
#include <pthread.h>
|
||||
|
||||
@@ -39,6 +39,6 @@ target_include_directories(ArmStateMachine PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
target_link_libraries(ArmStateMachine PUBLIC health_and_arming_checks)
|
||||
|
||||
px4_add_functional_gtest(SRC ArmStateMachineTest.cpp
|
||||
LINKLIBS ArmStateMachine health_and_arming_checks hysteresis sensor_calibration ArmAuthorization mode_util
|
||||
LINKLIBS ArmStateMachine health_and_arming_checks sensor_calibration ArmAuthorization mode_util
|
||||
)
|
||||
|
||||
|
||||
@@ -50,7 +50,6 @@ px4_add_module(
|
||||
esc_calibration.cpp
|
||||
factory_calibration_storage.cpp
|
||||
gyro_calibration.cpp
|
||||
HomePosition.cpp
|
||||
level_calibration.cpp
|
||||
lm_fit.cpp
|
||||
mag_calibration.cpp
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user