mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
gz: use server config file for loading world plugins (#24441)
Build all targets / Scan for Board Targets (push) Waiting to run
Build all targets / Build Group [${{ matrix.group }}] (push) Blocked by required conditions
Build all targets / Upload Artifacts to S3 (push) Blocked by required conditions
Build all targets / Create Release and Upload Artifacts (push) Blocked by required conditions
Checks / build (NO_NINJA_BUILD=1 px4_fmu-v5_default) (push) Waiting to run
Checks / build (NO_NINJA_BUILD=1 px4_sitl_default) (push) Waiting to run
Checks / build (check_format) (push) Waiting to run
Checks / build (check_newlines) (push) Waiting to run
Checks / build (module_documentation) (push) Waiting to run
Checks / build (px4_fmu-v2_default stack_check) (push) Waiting to run
Checks / build (px4_sitl_allyes) (push) Waiting to run
Checks / build (shellcheck_all) (push) Waiting to run
Checks / build (tests) (push) Waiting to run
Checks / build (tests_coverage) (push) Waiting to run
Checks / build (validate_module_configs) (push) Waiting to run
Clang Tidy / build (push) Waiting to run
MacOS build / build (px4_fmu-v5_default) (push) Waiting to run
MacOS build / build (px4_sitl) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Waiting to run
Container build / Build and Push Container (push) Waiting to run
EKF Update Change Indicator / unit_tests (push) Waiting to run
Failsafe Simulator Build / build (failsafe_web) (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Waiting to run
MAVROS Mission Tests / build (map[mission:MC_mission_box vehicle:iris]) (push) Waiting to run
MAVROS Mission Tests / build (map[mission:rover_mission_1 vehicle:rover]) (push) Waiting to run
MAVROS Offboard Tests / build (map[test_file:mavros_posix_tests_offboard_posctl.test vehicle:iris]) (push) Waiting to run
Nuttx Target with extra env config / build (px4_fmu-v5_default) (push) Waiting to run
Python CI Checks / build (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:humble ubuntu:jammy]) (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:jazzy ubuntu:noble]) (push) Waiting to run
SITL Tests / Testing PX4 tailsitter (push) Waiting to run
SITL Tests / Testing PX4 iris (push) Waiting to run
SITL Tests / Testing PX4 standard_vtol (push) Waiting to run
Build all targets / Scan for Board Targets (push) Waiting to run
Build all targets / Build Group [${{ matrix.group }}] (push) Blocked by required conditions
Build all targets / Upload Artifacts to S3 (push) Blocked by required conditions
Build all targets / Create Release and Upload Artifacts (push) Blocked by required conditions
Checks / build (NO_NINJA_BUILD=1 px4_fmu-v5_default) (push) Waiting to run
Checks / build (NO_NINJA_BUILD=1 px4_sitl_default) (push) Waiting to run
Checks / build (check_format) (push) Waiting to run
Checks / build (check_newlines) (push) Waiting to run
Checks / build (module_documentation) (push) Waiting to run
Checks / build (px4_fmu-v2_default stack_check) (push) Waiting to run
Checks / build (px4_sitl_allyes) (push) Waiting to run
Checks / build (shellcheck_all) (push) Waiting to run
Checks / build (tests) (push) Waiting to run
Checks / build (tests_coverage) (push) Waiting to run
Checks / build (validate_module_configs) (push) Waiting to run
Clang Tidy / build (push) Waiting to run
MacOS build / build (px4_fmu-v5_default) (push) Waiting to run
MacOS build / build (px4_sitl) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Waiting to run
Container build / Build and Push Container (push) Waiting to run
EKF Update Change Indicator / unit_tests (push) Waiting to run
Failsafe Simulator Build / build (failsafe_web) (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Waiting to run
MAVROS Mission Tests / build (map[mission:MC_mission_box vehicle:iris]) (push) Waiting to run
MAVROS Mission Tests / build (map[mission:rover_mission_1 vehicle:rover]) (push) Waiting to run
MAVROS Offboard Tests / build (map[test_file:mavros_posix_tests_offboard_posctl.test vehicle:iris]) (push) Waiting to run
Nuttx Target with extra env config / build (px4_fmu-v5_default) (push) Waiting to run
Python CI Checks / build (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:humble ubuntu:jammy]) (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:jazzy ubuntu:noble]) (push) Waiting to run
SITL Tests / Testing PX4 tailsitter (push) Waiting to run
SITL Tests / Testing PX4 iris (push) Waiting to run
SITL Tests / Testing PX4 standard_vtol (push) Waiting to run
* gz: use server config file for loading world plugins * submodule * use server.config in tree * newlines * format * gzbridge: rename function * format * gzbridge: add magnetometer callback * change gz_find_package to find_package * fix up directory structure and cmake to allow multiple plugins * newlines * add comment block explaining gz_env.sh * remove dupe readme * remove SENS_EN_MAGSIM from all gz airframe files except spacecraft * update gz submodule
This commit is contained in:
@@ -13,8 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500}
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
|
||||
|
||||
@@ -12,11 +12,8 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=rc_cessna}
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
param set-default SENS_EN_ARSPDSIM 1
|
||||
|
||||
|
||||
|
||||
param set-default FW_LND_ANG 8
|
||||
|
||||
param set-default NPFG_PERIOD 12
|
||||
|
||||
@@ -13,7 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol}
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
param set-default SENS_EN_ARSPDSIM 1
|
||||
|
||||
# TODO: Enable motor failure detection when the
|
||||
|
||||
@@ -14,8 +14,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=px4vision}
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
|
||||
# Commander Parameters
|
||||
param set-default COM_DISARM_LAND 0.5
|
||||
|
||||
|
||||
@@ -11,7 +11,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=advanced_plane}
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
param set-default SENS_EN_ARSPDSIM 1
|
||||
|
||||
param set-default FW_LND_ANG 8
|
||||
|
||||
@@ -45,9 +45,6 @@ param set-default PP_LOOKAHD_GAIN 1
|
||||
param set-default PP_LOOKAHD_MAX 10
|
||||
param set-default PP_LOOKAHD_MIN 1
|
||||
|
||||
# Simulated sensors
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
|
||||
# Actuator mapping
|
||||
param set-default SIM_GZ_WH_FUNC1 101 # right wheel
|
||||
param set-default SIM_GZ_WH_MIN1 70
|
||||
|
||||
@@ -11,8 +11,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=lawnmower}
|
||||
|
||||
param set-default SIM_GZ_EN 1 # Gazebo bridge
|
||||
|
||||
# Simulated sensors
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
# We can arm and drive in manual mode when it slides and GPS check fails:
|
||||
param set-default COM_ARM_WO_GPS 1
|
||||
|
||||
|
||||
@@ -44,9 +44,6 @@ param set-default PP_LOOKAHD_GAIN 1
|
||||
param set-default PP_LOOKAHD_MAX 10
|
||||
param set-default PP_LOOKAHD_MIN 1
|
||||
|
||||
# Simulated sensors
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
|
||||
# Wheels
|
||||
param set-default SIM_GZ_WH_FUNC1 101
|
||||
param set-default SIM_GZ_WH_MIN1 0
|
||||
|
||||
@@ -13,8 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadtailsitter}
|
||||
|
||||
param set-default SIM_GZ_EN 1 # Gazebo bridge
|
||||
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
|
||||
param set-default MAV_TYPE 20
|
||||
|
||||
param set-default CA_AIRFRAME 4
|
||||
|
||||
@@ -13,8 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=tiltrotor}
|
||||
|
||||
param set-default SIM_GZ_EN 1 # Gazebo bridge
|
||||
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
|
||||
param set-default MAV_TYPE 21
|
||||
|
||||
param set-default CA_AIRFRAME 3
|
||||
|
||||
@@ -83,7 +83,6 @@ param set-default CA_ROTOR7_AY -0.211325
|
||||
param set-default CA_ROTOR7_AZ -0.57735
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
|
||||
param set-default SIM_GZ_EC_FUNC1 101
|
||||
param set-default SIM_GZ_EC_FUNC2 102
|
||||
|
||||
Reference in New Issue
Block a user