From d111ea979d79a1da75a58fc65c28122625a96ef5 Mon Sep 17 00:00:00 2001 From: Balduin Date: Fri, 7 Mar 2025 14:42:14 +0100 Subject: [PATCH] Add world with moving platform (#83) New world moving_platform to simulate takeoff/landing on moving vehicle. Depends on MovingPlatformController plugin introduced in https://github.com/PX4/PX4-Autopilot/pull/24471. Launch using: PX4_GZ_MODEL_POSE=0,0,2.2,0,0,0 PX4_GZ_WORLD=moving_platform make px4_sitl gz_standard_vtol --- .gitignore | 1 + models/moving_platform/model.config | 4 ++ models/moving_platform/model.sdf | 48 ++++++++++++++ worlds/moving_platform.sdf | 97 +++++++++++++++++++++++++++++ 4 files changed, 150 insertions(+) create mode 100644 .gitignore create mode 100644 models/moving_platform/model.config create mode 100644 models/moving_platform/model.sdf create mode 100644 worlds/moving_platform.sdf diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..a75b99e --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +sdf_parsing/build/ diff --git a/models/moving_platform/model.config b/models/moving_platform/model.config new file mode 100644 index 0000000..052b4a1 --- /dev/null +++ b/models/moving_platform/model.config @@ -0,0 +1,4 @@ + + + model.sdf + diff --git a/models/moving_platform/model.sdf b/models/moving_platform/model.sdf new file mode 100644 index 0000000..ea72d54 --- /dev/null +++ b/models/moving_platform/model.sdf @@ -0,0 +1,48 @@ + + + + + + + + 5 5 0.1 + + + + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + 0.1 0.1 0.1 1 + + + + + + 5 5 0.1 + + + + 0 0 2 0 0 0 + + 10000 + + 10000 + 10000 + 10000 + + + + 1 + 30 + + + + + + + + + diff --git a/worlds/moving_platform.sdf b/worlds/moving_platform.sdf new file mode 100644 index 0000000..7ea1ae0 --- /dev/null +++ b/worlds/moving_platform.sdf @@ -0,0 +1,97 @@ + + + + + 0.004 + 1.0 + 250 + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + false + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + true + + + true + + + + + 0 0 1 + 1 1 + + + + + + + + + + + + + + 0 0 1 + 500 500 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + + 1 + 0 + 0 + 1 + 0 + 1 + + + false + + 0 0 0 0 -0 0 + false + + + model://moving_platform + + + 0 0 500 0 -0 0 + true + 1 + 0.001 0.625 -0.78 + 0.904 0.904 0.904 1 + 0.271 0.271 0.271 1 + + 2000 + 0 + 1 + 0 + + + 0 + 0 + 0 + + + + EARTH_WGS84 + ENU + 47.397971057728974 + 8.546163739800146 + 0 + + +