Skip to content

Commit

Permalink
Cleanup models (#35)
Browse files Browse the repository at this point in the history
- 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 <[email protected]>
  • Loading branch information
srmainwaring authored Dec 16, 2022
1 parent 8f3970a commit 1808aba
Show file tree
Hide file tree
Showing 18 changed files with 832 additions and 922 deletions.
62 changes: 54 additions & 8 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -92,33 +90,81 @@ 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
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 `<physics>` element configured to run
faster than real time:

```xml
<physics name="1ms" type="ignore">
<max_step_size>0.001</max_step_size>
<real_time_factor>-1.0</real_time_factor>
</physics>
```

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
Expand Down
2 changes: 1 addition & 1 deletion models/runway/model.config
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<model>
<name>Runway</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>
<sdf version="1.7">model.sdf</sdf>

<author>
<name>Rhys Mainwaring</name>
Expand Down
4 changes: 2 additions & 2 deletions models/runway/model.sdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version='1.0'?>
<sdf version="1.6">
<sdf version="1.7">
<model name="runway">
<static>true</static>
<link name="link">
Expand Down Expand Up @@ -34,7 +34,7 @@
</material>
</visual>
<visual name="airfield">
<pose>0 0 -0.5 0 0 0</pose>
<pose>0 0 -0.01 0 0 0</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<mesh>
Expand Down
File renamed without changes
File renamed without changes.
24 changes: 24 additions & 0 deletions models/zephyr/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<?xml version="1.0"?>

<model>
<name>Zephyr Delta Wing</name>
<version>1.0</version>
<sdf version="1.7">model.sdf</sdf>

<author>
<name>Cole Biesemeyer</name>
<email>[email protected]</email>
</author>

<author>
<name>Nate Koenig</name>
<email>[email protected]</email>
</author>

<description>
A model of a Zephyr delta wing.

Updated materials for Gazebo Sim.
</description>

</model>
Loading

0 comments on commit 1808aba

Please sign in to comment.