From 1808abac87aef4097b912e4b5668f042f8f54d5a Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Fri, 16 Dec 2022 16:23:29 +0000 Subject: [PATCH] Cleanup models (#35) - Remove cmac world - StaticMapPlugin not available in Gazebo Sim - Rename world files and use .sdf suffix. - Update runway model - reduce the gap between the airstrip and ground as upstream z-order has been fixed. - Update zephyr runway world - remove commented out pose. - Update iris warehouse world - remove models that do not load because of incorrect server details. - Split zephyr model into a base model and plugin model with ardupilot integration. - Set zephyr runway model to run with RTF > 1 - Update README - describe how to run the zephyr model. Signed-off-by: Rhys Mainwaring --- README.md | 62 ++- models/runway/model.config | 2 +- models/runway/model.sdf | 4 +- .../materials/textures/wing.png | Bin .../meshes/wing.dae | 0 models/zephyr/model.config | 24 + models/zephyr/model.sdf | 285 +++++++++++ .../thumbnails/1.png | Bin .../thumbnails/2.png | Bin .../thumbnails/3.png | Bin .../thumbnails/4.png | Bin .../thumbnails/5.png | Bin models/zephyr_with_ardupilot/model.sdf | 416 +--------------- worlds/iris_arducopter_cmac.world | 51 -- worlds/iris_arducopter_edifice_demo.world | 459 ------------------ ...rducopter_runway.world => iris_runway.sdf} | 7 +- worlds/iris_warehouse.sdf | 435 +++++++++++++++++ ...duplane_runway.world => zephyr_runway.sdf} | 9 +- 18 files changed, 832 insertions(+), 922 deletions(-) rename models/{zephyr_with_ardupilot => zephyr}/materials/textures/wing.png (100%) rename models/{zephyr_with_ardupilot => zephyr}/meshes/wing.dae (100%) create mode 100644 models/zephyr/model.config create mode 100644 models/zephyr/model.sdf rename models/{zephyr_with_ardupilot => zephyr}/thumbnails/1.png (100%) rename models/{zephyr_with_ardupilot => zephyr}/thumbnails/2.png (100%) rename models/{zephyr_with_ardupilot => zephyr}/thumbnails/3.png (100%) rename models/{zephyr_with_ardupilot => zephyr}/thumbnails/4.png (100%) rename models/{zephyr_with_ardupilot => zephyr}/thumbnails/5.png (100%) delete mode 100755 worlds/iris_arducopter_cmac.world delete mode 100644 worlds/iris_arducopter_edifice_demo.world rename worlds/{iris_arducopter_runway.world => iris_runway.sdf} (86%) create mode 100644 worlds/iris_warehouse.sdf rename worlds/{zephyr_arduplane_runway.world => zephyr_runway.sdf} (87%) diff --git a/README.md b/README.md index 29e6439..caa1101 100644 --- a/README.md +++ b/README.md @@ -65,9 +65,7 @@ cmake .. -DCMAKE_BUILD_TYPE=RelWithDebInfo make -j4 ``` -## Usage - -### Configure environment +## Configure Set the Gazebo environment variables in your `.bashrc` or `.zshrc` or in the terminal used to run Gazebo. @@ -92,26 +90,30 @@ echo 'export GZ_SIM_RESOURCE_PATH=$HOME/ardupilot_gazebo/models:$HOME/ardupilot_ Reload your terminal with `source ~/.bashrc` (or `source ~/.zshrc` on macOS). -### Run Gazebo +## Usage + +### 1. Iris quad-copter + +#### Run Gazebo ```bash -gz sim -v4 -r iris_arducopter_runway.world +gz sim -v4 -r iris_runway.sdf ``` The `-v4` parameter is not mandatory, it shows additional information and is useful for troubleshooting. -### Run ArduPilot SITL +#### Run ArduPilot SITL To run an ArduPilot simulation with Gazebo, the frame should have `gazebo-` in it and have `JSON` as model. Other commandline parameters are the same -as usal on SITL. +as usual on SITL. ```bash sim_vehicle.py -v ArduCopter -f gazebo-iris --model JSON --map --console ``` -### Arm and takeoff +#### Arm and takeoff ```bash STABILIZE> mode guided @@ -119,6 +121,50 @@ GUIDED> arm throttle GUIDED> takeoff 5 ``` +### 2. Zephyr delta wing + +The Zephyr delta wing is positioned on the runway for vertical take-off. + +#### Run Gazebo + +```bash +gz sim -v4 -r zephyr_runway.sdf +``` + +#### Run ArduPilot SITL + +```bash +sim_vehicle.py -v ArduPlane -f gazebo-zephyr --model JSON --map --console +``` + +#### Arm, takeoff and circle + +```bash +MANUAL> mode fbwa +FBWA> arm throttle +FBWA> rc 3 1800 +FBWA> mode circle +``` + +#### Increase the simulation speed + +The `zephyr_runway.sdf` world has a `` element configured to run +faster than real time: + +```xml + + 0.001 + -1.0 + +``` + +To see the effect of the speed-up set the param `SIM_SPEEDUP` to a value +greater than one: + +```bash +MANUAL> param set SIM_SPEEDUP 10 +``` + ## Troubleshooting For issues concerning installing and running Gazebo on your platform please diff --git a/models/runway/model.config b/models/runway/model.config index cfe70c1..5548d70 100755 --- a/models/runway/model.config +++ b/models/runway/model.config @@ -2,7 +2,7 @@ Runway 1.0 - model.sdf + model.sdf Rhys Mainwaring diff --git a/models/runway/model.sdf b/models/runway/model.sdf index cc892b3..bbe2be2 100755 --- a/models/runway/model.sdf +++ b/models/runway/model.sdf @@ -1,5 +1,5 @@ - + true @@ -34,7 +34,7 @@ - 0 0 -0.5 0 0 0 + 0 0 -0.01 0 0 0 false diff --git a/models/zephyr_with_ardupilot/materials/textures/wing.png b/models/zephyr/materials/textures/wing.png similarity index 100% rename from models/zephyr_with_ardupilot/materials/textures/wing.png rename to models/zephyr/materials/textures/wing.png diff --git a/models/zephyr_with_ardupilot/meshes/wing.dae b/models/zephyr/meshes/wing.dae similarity index 100% rename from models/zephyr_with_ardupilot/meshes/wing.dae rename to models/zephyr/meshes/wing.dae diff --git a/models/zephyr/model.config b/models/zephyr/model.config new file mode 100644 index 0000000..308325c --- /dev/null +++ b/models/zephyr/model.config @@ -0,0 +1,24 @@ + + + + Zephyr Delta Wing + 1.0 + model.sdf + + + Cole Biesemeyer + cole.bsmr@gmail.com + + + + Nate Koenig + natekoenig@gmail.com + + + + A model of a Zephyr delta wing. + + Updated materials for Gazebo Sim. + + + diff --git a/models/zephyr/model.sdf b/models/zephyr/model.sdf new file mode 100644 index 0000000..711d3ba --- /dev/null +++ b/models/zephyr/model.sdf @@ -0,0 +1,285 @@ + + + + + + 0 -0.12 0 0 0 0 + 1.5 + + 0.083137104 + 0 + 0.387382402 + 0 + 0 + 0.469845106 + + + + + + model://zephyr/meshes/wing.dae + + Wing +
true
+
+
+
+
+ + + + model://zephyr/meshes/wing.dae + + Wing +
true
+
+
+
+
+ + -0.76435 0.33918 0.002 -0.03 0 0 + + + .005 0.12993 .12688 + + + + + 0.76435 0.33918 0.002 -0.03 0 0 + + + .005 0.12993 .12688 + + + + + + + 0 -0.1 0.0 0 0 0 + + + 0.03 + + + + 0 0 1 + 0 0 1 + 0.1 0.1 0.1 1 + + + + 0.7 0.20 0 0 0 0 + + + 0.03 + + + + 1 0 0 + 1 0 0 + 0.1 0.1 0.1 1 + + + + -0.7 0.20 0 0 0 0 + + + 0.03 + + + + 0 1 0 + 0 1 0 + 0.1 0.1 0.1 1 + + + + + + 0 0.07 0.008 0 1.5707 0 + + .05 + + 0.000367571 + 0 + 0.00036985 + 0 + 0 + 0.000003187 + + + + + + model://zephyr/meshes/wing.dae + + Propeller +
true
+
+
+
+
+ + 0 0 0.074205 0 0 0.3 + + + 0.02561 0.00541 0.14841 + + + + + 0 0 -0.074205 0 0 -0.3 + + + 0.02561 0.00541 0.14841 + + + + + + 0.4530 .239 0.007 0 0 0 + + 0 0 0 0 0 0.32445671 + .1 + + 0.000102319 + 0 + 0.00334417 + 0 + 0 + 0.003446072 + + + + + + model://zephyr/meshes/wing.dae + + Flap_Left +
true
+
+
+
+
+ + -0.01 0.01 0 0 0 0.32445671 + + + 0.633463031 0.110694312 0.005 + + + + + + -0.4530 .239 0.007 0 0 0 + + 0 0 0 0 0 -0.32445671 + .1 + + 0.000102319 + 0 + 0.00334417 + 0 + 0 + 0.003446072 + + + + + + model://zephyr/meshes/wing.dae + + Flap_Right +
true
+
+
+
+
+ + 0.01 0.01 0 0 0 -0.32445671 + + + 0.633463031 0.110694312 0.005 + + + + + + wing + propeller + + 0 -1 0 + + 0.002 + + + + + wing + flap_left + 0 -0.04 0 0 0 0 + + 1 0.330321014 0 + + -0.524 + 0.524 + + + 0.1 + + + + + wing + flap_right + 0 -0.04 0 0 0 0 + + 1 -0.330321014 0 + + -0.524 + 0.524 + + + 0.1 + + + + + + + + 0 0 0 0 0 0 + 0.15 + + 0.00002 + 0 + 0 + 0.00002 + 0 + 0.00002 + + + + 0 0 0 3.141593 0 -1.5707963 + 1 + 1000.0 + + + + imu_link + wing + + 0 0 1 + + 0 + 0 + 0 + 0 + + + 1.0 + + + +
+
diff --git a/models/zephyr_with_ardupilot/thumbnails/1.png b/models/zephyr/thumbnails/1.png similarity index 100% rename from models/zephyr_with_ardupilot/thumbnails/1.png rename to models/zephyr/thumbnails/1.png diff --git a/models/zephyr_with_ardupilot/thumbnails/2.png b/models/zephyr/thumbnails/2.png similarity index 100% rename from models/zephyr_with_ardupilot/thumbnails/2.png rename to models/zephyr/thumbnails/2.png diff --git a/models/zephyr_with_ardupilot/thumbnails/3.png b/models/zephyr/thumbnails/3.png similarity index 100% rename from models/zephyr_with_ardupilot/thumbnails/3.png rename to models/zephyr/thumbnails/3.png diff --git a/models/zephyr_with_ardupilot/thumbnails/4.png b/models/zephyr/thumbnails/4.png similarity index 100% rename from models/zephyr_with_ardupilot/thumbnails/4.png rename to models/zephyr/thumbnails/4.png diff --git a/models/zephyr_with_ardupilot/thumbnails/5.png b/models/zephyr/thumbnails/5.png similarity index 100% rename from models/zephyr_with_ardupilot/thumbnails/5.png rename to models/zephyr/thumbnails/5.png diff --git a/models/zephyr_with_ardupilot/model.sdf b/models/zephyr_with_ardupilot/model.sdf index fda1170..940e2b3 100644 --- a/models/zephyr_with_ardupilot/model.sdf +++ b/models/zephyr_with_ardupilot/model.sdf @@ -1,387 +1,9 @@ - 0 0 0 0 0 0 - - - 0 -0.12 0 0 0 0 - 1.5 - - 0.083137104 - 0 - 0.387382402 - 0 - 0 - 0.469845106 - - - - - - model://zephyr_with_ardupilot/meshes/wing.dae - - Wing -
true
-
-
-
-
- - - - model://zephyr_with_ardupilot/meshes/wing.dae - - Wing -
true
-
-
-
-
- - -0.76435 0.33918 0.002 -0.03 0 0 - - - .005 0.12993 .12688 - - - - - 0.76435 0.33918 0.002 -0.03 0 0 - - - .005 0.12993 .12688 - - - - - - 0 -0.1 0.0 0 0 0 - - - 0.03 - - - - 0 0 1 - 0 0 1 - 0.1 0.1 0.1 1 - - - - 0.7 0.20 0 0 0 0 - - - 0.03 - - - - 1 0 0 - 1 0 0 - 0.1 0.1 0.1 1 - - - - -0.7 0.20 0 0 0 0 - - - 0.03 - - - - 0 1 0 - 0 1 0 - 0.1 0.1 0.1 1 - - - - - - - - 0 0.07 0.008 0 1.5707 0 - - .05 - - 0.000367571 - 0 - 0.00036985 - 0 - 0 - 0.000003187 - - - - - - model://zephyr_with_ardupilot/meshes/wing.dae - - Propeller -
true
-
-
-
-
- - 0 0 0.074205 0 0 0.3 - - - 0.02561 0.00541 0.14841 - - - - - 0 0 -0.074205 0 0 -0.3 - - - 0.02561 0.00541 0.14841 - - - - - - - 0.4530 .239 0.007 0 0 0 - - 0 0 0 0 0 0.32445671 - .1 - - 0.000102319 - 0 - 0.00334417 - 0 - 0 - 0.003446072 - - - - - - model://zephyr_with_ardupilot/meshes/wing.dae - - Flap_Left -
true
-
-
-
-
- - -0.01 0.01 0 0 0 0.32445671 - - - 0.633463031 0.110694312 0.005 - - - - - - -0.4530 .239 0.007 0 0 0 - - 0 0 0 0 0 -0.32445671 - .1 - - 0.000102319 - 0 - 0.00334417 - 0 - 0 - 0.003446072 - - - - - - model://zephyr_with_ardupilot/meshes/wing.dae - - Flap_Right -
true
-
-
-
-
- - 0.01 0.01 0 0 0 -0.32445671 - - - 0.633463031 0.110694312 0.005 - - - - - - wing - propeller - - 0 -1 0 - - 0.002 - - - - - wing - flap_left - 0 -0.04 0 0 0 0 - - 1 0.330321014 0 - - -0.524 - 0.524 - - - 0.1 - - - - - wing - flap_right - 0 -0.04 0 0 0 0 - - 1 -0.330321014 0 - - -0.524 - 0.524 - - - 0.1 - - - - - - - - 0 0 0 0 0 0 - 0.15 - - 0.00002 - 0 - 0 - 0.00002 - 0 - 0.00002 - - - - 0 0 0 3.141593 0 -1.5707963 - 1 - 1000.0 - - - - imu_link - wing - - 0 0 1 - - 0 - 0 - 0 - 0 - - - 1.0 - - 1 - - + + model://zephyr + 1.2041 0 -1 0 0 0 1 - wing + zephyr::wing 1.2041 0 -1 0 0 0 1 - wing - flap_left_joint + zephyr::wing + zephyr::flap_left_joint -5.0 @@ -441,8 +63,8 @@ 1.2041 0 -1 0 0 0 1 - wing - flap_right_joint + zephyr::wing + zephyr::flap_right_joint -5.0 @@ -461,7 +83,7 @@ 1.2041 0 -1 0 1 0 0 - wing + zephyr::wing 1.2041 0 -1 0 1 0 0 - wing + zephyr::wing 0 0 0.074205 -1 0 0 0 -1 0 - propeller + zephyr::propeller 0 0 -0.074205 1 0 0 0 -1 0 - propeller + zephyr::propeller - propeller_joint + zephyr::propeller_joint - flap_left_joint + zephyr::flap_left_joint - flap_right_joint + zephyr::flap_right_joint @@ -552,7 +174,7 @@ 0 0 0 3.141593 0 0 - imu_sensor + zephyr::imu_link::imu_sensor - propeller_joint + zephyr::propeller_joint 1 838 0 @@ -600,7 +222,7 @@ scale: 0.524 => [-0.524, 0.524] --> - flap_left_joint + zephyr::flap_left_joint 1 -1.048 -0.5 @@ -624,7 +246,7 @@ SERVO2_TRIM 1500 --> - flap_right_joint + zephyr::flap_right_joint 1 -1.048 -0.5 diff --git a/worlds/iris_arducopter_cmac.world b/worlds/iris_arducopter_cmac.world deleted file mode 100755 index 621a2b2..0000000 --- a/worlds/iris_arducopter_cmac.world +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - -5 0 1 0 0.2 0 - - - - - - quick - 100 - 1.0 - - - 0.0 - 0.2 - 0.1 - 0.0 - - - -1 - - - 0 0 -9.8 - - model://sun - - - - model://ground_plane - - - - -
-35.363261 149.165230
- 300 - satellite - YOU_API_KEY - true - 0 0 0.2 0 0 -1.5708 -
- - - - model://iris_with_ardupilot - - -
-
diff --git a/worlds/iris_arducopter_edifice_demo.world b/worlds/iris_arducopter_edifice_demo.world deleted file mode 100644 index 0495bf6..0000000 --- a/worlds/iris_arducopter_edifice_demo.world +++ /dev/null @@ -1,459 +0,0 @@ - - - - - false - - - 0.002 - 1.0 - - - - - ogre2 - - - - - - - - - - - - - - - 3D View - false - docked - - - ogre2 - scene - 0.4 0.4 0.4 - 0.8 0.8 0.8 - 6 0 6 0 0.5 3.14 - - - - - - World control - false - false - 72 - 121 - 1 - - floating - - - - - - - true - true - true - - - - - - - - floating - 5 - 5 - false - - - - - false - 5 - 5 - floating - false - - - - - false - 5 - 5 - floating - false - - - - - false - 5 - 5 - floating - false - - - - - false - 5 - 5 - floating - false - - - - - - - - - false - 5 - 5 - floating - false - - - - - false - 5 - 5 - floating - false - - - - - - - - - - false - 5 - 5 - floating - false - - - - - - - World stats - false - false - 110 - 290 - 1 - - floating - - - - - - - true - true - true - true - - - - - - - false - 0 - 0 - 250 - 50 - floating - false - #666666 - - - - - - - false - 250 - 0 - 150 - 50 - floating - false - #666666 - - - - - - - - - - false - 250 - 50 - 50 - 50 - floating - false - #777777 - - - - - - - false - docked - - - - - - - false - docked - - - - - - - docked_collapsed - - - - - - - docked_collapsed - - Panda - - - - - - - - - - false - 5 - 5 - floating - false - - - - - - - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Depot - - - - -6 0 0.25 0 0 0 - model://iris_with_standoffs - - - - -9.4 1.6 0 0 0 -0.5 - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Mecanum lift - - - - -13.2 -6.0 0.15 0 0 0 - https://fuel.gazebosim.org/1.0/OpenRobotics/models/fog emitter - - - - -9.0 -1.8 1.038 0 0 0 - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Panda with Ignition position controller model - - - - -9.0 -2.4 0 0 0 1.57 - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Reflective table - - - - -13.2 -6.0 0 0 0 1.57 - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Rescue Randy Sitting - - - - -9.0 -6.21 5.0 0 0.9 -3.14 - true - https://fuel.gazebosim.org/1.0/OpenRobotics/models/16-Bit Thermal Camera - - - - -9.0 -5.95 5.0 0 0.9 -3.14 - true - https://fuel.gazebosim.org/1.0/OpenRobotics/models/8-Bit Thermal Camera - - - - -9.075 -6.15 4.995 0 0.9 -3.14 - true - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Camera - - - - -9.04 -6.04 4.97 0 0.9 -3.14 - true - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Depth Camera - - - - - -13.2 -5.3 0.2 0 0 0 - - - - 1 - 0 - 0 - 1 - 0 - 1 - - 1.0 - - - - - 0.4 0.4 0.4 - - - - - - - - 0.4 0.4 0.4 - - - - 1 0 0 1 - 1 0 0 1 - 1 0 0 1 - - - 295.0 - - - - - - - - - - - 87 - - - linear: {x: 1.0, y: 0.0}, angular: {z: 0.0} - - - - - - - 88 - - - linear: {x: -1.0, y: 0.0}, angular: {z: 0.0} - - - - - - - 68 - - - linear: {x: 0.0, y: -1.0}, angular: {z: 0.0} - - - - - - - 65 - - - linear: {x: 0.0, y: 1.0}, angular: {z: 0.0} - - - - - - - 69 - - - linear: {x: 0.0, y: 0.0}, angular: {z: -1.0} - - - - - - - 81 - - - linear: {x: 0.0, y: 0.0}, angular: {z: 1.0} - - - - - - - 83 - - - linear: {x: 0.0, y: 0.0}, angular: {z: 0.0} - - - - - diff --git a/worlds/iris_arducopter_runway.world b/worlds/iris_runway.sdf similarity index 86% rename from worlds/iris_arducopter_runway.world rename to worlds/iris_runway.sdf index b621fd0..56c60f1 100755 --- a/worlds/iris_arducopter_runway.world +++ b/worlds/iris_runway.sdf @@ -1,6 +1,11 @@ - + + + 0.001 + 1.0 + + diff --git a/worlds/iris_warehouse.sdf b/worlds/iris_warehouse.sdf new file mode 100644 index 0000000..d59e925 --- /dev/null +++ b/worlds/iris_warehouse.sdf @@ -0,0 +1,435 @@ + + + + + 0.001 + 1.0 + + + + + + ogre2 + + + + + + + + + + false + + + + + + 3D View + false + docked + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + 6 0 6 0 0.5 3.14 + + + + World control + false + false + 72 + 145 + 1 + floating + + + + + + true + true + true + + + + floating + 5 + 5 + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + + + false + 5 + 5 + floating + false + + + + + World stats + false + false + 110 + 290 + 1 + floating + + + + + + true + true + true + true + + + + false + 0 + 0 + 250 + 50 + floating + false + #666666 + + + + + false + 250 + 0 + 150 + 50 + floating + false + #666666 + + + + + false + 0 + 50 + 250 + 50 + floating + false + #777777 + + + + + false + 250 + 50 + 50 + 50 + floating + false + #777777 + + + + + true + docked + + + + + true + docked + + + + + docked_collapsed + + + + + + + + + + false + 5 + 5 + floating + false + + + + + + -6 0 0.25 0 0 0 + model://iris_with_ardupilot + + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Depot + + + + -9.4 1.6 0 0 0 -0.5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Mecanum lift + + + + -13.2 -6.0 0.15 0 0 0 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/fog emitter + + + + + + + + + + -9.0 -6.21 5.0 0 0.9 -3.14 + true + https://fuel.gazebosim.org/1.0/OpenRobotics/models/16-Bit Thermal Camera + + + + -9.0 -5.95 5.0 0 0.9 -3.14 + true + https://fuel.gazebosim.org/1.0/OpenRobotics/models/8-Bit Thermal Camera + + + + -9.075 -6.15 4.995 0 0.9 -3.14 + true + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Camera + + + + -9.04 -6.04 4.97 0 0.9 -3.14 + true + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Depth Camera + + + + + -13.2 -5.3 0.2 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 0.4 0.4 0.4 + + + + + + + + 0.4 0.4 0.4 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + 285.0 + + + + + + + + + + + 87 + + + linear: {x: 1.0, y: 0.0}, angular: {z: 0.0} + + + + + + + 88 + + + linear: {x: -1.0, y: 0.0}, angular: {z: 0.0} + + + + + + + 68 + + + linear: {x: 0.0, y: -1.0}, angular: {z: 0.0} + + + + + + + 65 + + + linear: {x: 0.0, y: 1.0}, angular: {z: 0.0} + + + + + + + 69 + + + linear: {x: 0.0, y: 0.0}, angular: {z: -1.0} + + + + + + + 81 + + + linear: {x: 0.0, y: 0.0}, angular: {z: 1.0} + + + + + + + 83 + + + linear: {x: 0.0, y: 0.0}, angular: {z: 0.0} + + + + + diff --git a/worlds/zephyr_arduplane_runway.world b/worlds/zephyr_runway.sdf similarity index 87% rename from worlds/zephyr_arduplane_runway.world rename to worlds/zephyr_runway.sdf index 159717b..830a45d 100755 --- a/worlds/zephyr_arduplane_runway.world +++ b/worlds/zephyr_runway.sdf @@ -1,6 +1,11 @@ - + + + 0.001 + -1.0 + + @@ -38,10 +43,8 @@ model://runway - 0 0 0.422 -1.5707963 0 1.5707963 - model://zephyr_with_ardupilot