Skip to content

Commit

Permalink
Models: update world orientation and fixes for Harmonic
Browse files Browse the repository at this point in the history
- Anemometer: use degrees.
- Gimbal 1D: use degrees in pose.
- Gimbal 2D: use degrees in pose.
- Parachute: update plugin filename.
- Iris: use degrees, replace -0 with 0.
- Iris: remove z-offset from iris_with_standoffs model.
  - Remove z-offset from iris_with_standoffs, so model origin is at CoM.
  - Set pose in world file.
- Zephyr: use degrees.
- Zephyr: update parachute plugin name.
- Zephyr: disable moment coefficient contribution.
  - Required due to changed behaviour in Gazebo Harmonic.
- Update gimbal pose in iris_with_gimbal world.
- Update iris_warehouse world.
- Forward port remaining changes from `main`.

Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Dec 21, 2023
1 parent aa819ff commit fff0ee5
Show file tree
Hide file tree
Showing 17 changed files with 336 additions and 169 deletions.
2 changes: 1 addition & 1 deletion models/gimbal_small_1d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@
</geometry>
</collision>
<sensor name="camera" type="camera">
<pose>0 0 0 -1.57 -1.57 0</pose>
<pose degrees="true">0 0 0 -90 -90 0</pose>
<camera>
<horizontal_fov>2.0</horizontal_fov>
<image>
Expand Down
2 changes: 1 addition & 1 deletion models/gimbal_small_2d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@
</geometry>
</collision>
<sensor name="camera" type="camera">
<pose>0 0 0 -1.57 -1.57 0</pose>
<pose degrees="true">0 0 0 -90 -90 0</pose>
<camera>
<horizontal_fov>2.0</horizontal_fov>
<image>
Expand Down
Loading

0 comments on commit fff0ee5

Please sign in to comment.