Skip to content

Commit

Permalink
Merge branch 'gz-sim9' into arjo/fix/a_hack_to_greatly_improve_loadtimes
Browse files Browse the repository at this point in the history
  • Loading branch information
arjo129 authored Oct 1, 2024
2 parents beadb78 + bbe2cc6 commit 4a833ac
Show file tree
Hide file tree
Showing 55 changed files with 974 additions and 176 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ find_package(gz-cmake4 REQUIRED)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

gz_configure_project(VERSION_SUFFIX pre1)
gz_configure_project(VERSION_SUFFIX)

#============================================================================
# Set project-specific options
Expand Down
75 changes: 74 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
@@ -1,9 +1,82 @@
## Gazebo Sim 9.x

### Gazebo Sim 9.0.0 (2024-09-XX)
### Gazebo Sim 9.0.0 (2024-09-25)

1. **Baseline:** this includes all changes from 8.6.0 and earlier.

1. Miscellaneous documentation fixes
* [Pull request #2634](https://github.com/gazebosim/gz-sim/pull/2634)
* [Pull request #2632](https://github.com/gazebosim/gz-sim/pull/2632)
* [Pull request #2628](https://github.com/gazebosim/gz-sim/pull/2628)
* [Pull request #2631](https://github.com/gazebosim/gz-sim/pull/2631)
* [Pull request #2627](https://github.com/gazebosim/gz-sim/pull/2627)
* [Pull request #2625](https://github.com/gazebosim/gz-sim/pull/2625)
* [Pull request #2622](https://github.com/gazebosim/gz-sim/pull/2622)
* [Pull request #2607](https://github.com/gazebosim/gz-sim/pull/2607)
* [Pull request #2606](https://github.com/gazebosim/gz-sim/pull/2606)
* [Pull request #2602](https://github.com/gazebosim/gz-sim/pull/2602)
* [Pull request #2601](https://github.com/gazebosim/gz-sim/pull/2601)
* [Pull request #2603](https://github.com/gazebosim/gz-sim/pull/2603)
* [Pull request #2578](https://github.com/gazebosim/gz-sim/pull/2578)
* [Pull request #2592](https://github.com/gazebosim/gz-sim/pull/2592)
* [Pull request #2582](https://github.com/gazebosim/gz-sim/pull/2582)
* [Pull request #2585](https://github.com/gazebosim/gz-sim/pull/2585)
* [Pull request #2576](https://github.com/gazebosim/gz-sim/pull/2576)
* [Pull request #2573](https://github.com/gazebosim/gz-sim/pull/2573)
* [Pull request #2571](https://github.com/gazebosim/gz-sim/pull/2571)
* [Pull request #2574](https://github.com/gazebosim/gz-sim/pull/2574)
* [Pull request #2564](https://github.com/gazebosim/gz-sim/pull/2564)
* [Pull request #2563](https://github.com/gazebosim/gz-sim/pull/2563)
* [Pull request #2562](https://github.com/gazebosim/gz-sim/pull/2562)
* [Pull request #2553](https://github.com/gazebosim/gz-sim/pull/2553)

1. Fix log playback GUI display
* [Pull request #2611](https://github.com/gazebosim/gz-sim/pull/2611)
* [Pull request #2619](https://github.com/gazebosim/gz-sim/pull/2619)

1. Add tutorial + example SDF for shadow texture size
* [Pull request #2597](https://github.com/gazebosim/gz-sim/pull/2597)

1. Fix making breadcrumb static if it's a nested model
* [Pull request #2593](https://github.com/gazebosim/gz-sim/pull/2593)

1. Update physics system error msg when plugin can not be loaded
* [Pull request #2604](https://github.com/gazebosim/gz-sim/pull/2604)

1. Fix configuring global illumination GUI plugin parameters
* [Pull request #2594](https://github.com/gazebosim/gz-sim/pull/2594)

1. Fix particle emitter color range image path warning
* [Pull request #2560](https://github.com/gazebosim/gz-sim/pull/2560)

1. Fix empty gui world file
* [Pull request #2591](https://github.com/gazebosim/gz-sim/pull/2591)

1. Fix crash on windows due to invalid log directory path
* [Pull request #2589](https://github.com/gazebosim/gz-sim/pull/2589)

1. Use ogre2 for DEM worlds
* [Pull request #2586](https://github.com/gazebosim/gz-sim/pull/2586)

1. Fix crash when running the optical tactile sensor world
* [Pull request #2561](https://github.com/gazebosim/gz-sim/pull/2561)

1. Prevent follow actor plugin from crashing when actor is removed
* [Pull request #2577](https://github.com/gazebosim/gz-sim/pull/2577)
* [Pull request #2584](https://github.com/gazebosim/gz-sim/pull/2584)

1. Fix hydrodynamics deprecation warning.
* [Pull request #2579](https://github.com/gazebosim/gz-sim/pull/2579)

1. Removed actor population world due to bad merge
* [Pull request #2581](https://github.com/gazebosim/gz-sim/pull/2581)

1. Fixed warning joint trayectory sdf
* [Pull request #2580](https://github.com/gazebosim/gz-sim/pull/2580)

1. Fix looking up camera name in camera lens system
* [Pull request #2559](https://github.com/gazebosim/gz-sim/pull/2559)

1. Add a flexible mechanism to combine user and default plugins
* [Pull request #2497](https://github.com/gazebosim/gz-sim/pull/2497)

Expand Down
41 changes: 16 additions & 25 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,10 @@ Gazebo Sim is derived from [Gazebo Classic](http://classic.gazebosim.org) and re

[Folder Structure](#folder-structure)

[Code of Conduct](#code-of-conduct)

[Contributing](#contributing)

[Code of Conduct](#code-of-conduct)

[Versioning](#versioning)

[License](#license)
Expand Down Expand Up @@ -99,29 +99,20 @@ gz sim -h
In the event that the installation is a mix of Debian and from source, command
line tools from `gz-tools` may not work correctly.

A workaround for a single package is to define the environment variable
`GZ_CONFIG_PATH` to point to the location of the Gazebo library installation,
where the YAML file for the package is found, such as
A workaround is to define the environment variable
`GZ_CONFIG_PATH` to point to the different locations of the Gazebo libraries installations,
where the YAML files for the packages are found, such as
```
export GZ_CONFIG_PATH=/usr/local/share/gz
export GZ_CONFIG_PATH=/usr/local/share/gz:$HOME/ws/install/share/gz
```

However, that environment variable only takes a single path, which means if the
installations from source are in different locations, only one can be specified.
where `$HOME/ws` is an example colcon workspace used to build Gazebo.

Another workaround for working with multiple Gazebo libraries on the command
line is using symbolic links to each library's YAML file.
```
mkdir ~/.gz/tools/configs -p
cd ~/.gz/tools/configs/
ln -s /usr/local/share/gz/fuel8.yaml .
ln -s /usr/local/share/gz/transport14.yaml .
ln -s /usr/local/share/gz/transportlog13.yaml .
...
export GZ_CONFIG_PATH=$HOME/.gz/tools/configs
```

This issue is tracked [here](https://github.com/gazebosim/gz-tools/issues/8).
On Windows, `gz sim` (i.e. running both server and GUI in one command) doesn't yet work.
To run Gazebo Sim on Windows, you need to run the server in one terminal (`gz sim -s <other args>`)
and the GUI in another terminal (`gz sim -g <other args>`). Remember this when reading through
all Gazebo Sim tutorials. Also remember that Conda and `install\setup.bat` need to be sourced
in both terminals (as well as any changes to `GZ_PARTITION` and other environment variables).

# Documentation

Expand All @@ -131,7 +122,7 @@ See the [installation tutorial](https://gazebosim.org/api/sim/9/install.html).

See the [installation tutorial](https://gazebosim.org/api/sim/9/install.html).

See the [Writing Tests section of the contributor guide](https://github.com/gazebosim/gz-sim/blob/main/CONTRIBUTING.md#writing-tests) for help creating or modifying tests.
See the [Writing Tests section of the contributor guide](https://gazebosim.org/docs/all/contributing/#writing-tests) for help creating or modifying tests.

# Folder Structure

Expand All @@ -154,7 +145,7 @@ gz-sim
│   ├── performance Performance tests.
│   ├── plugins Plugins used in tests.
│   ├── regression Regression tests.
│   └── tutorials Tutorials, written in markdown.
── tutorials Tutorials, written in markdown.
├── Changelog.md Changelog.
├── CMakeLists.txt CMake build script.
├── Migration.md Migration guide.
Expand All @@ -163,8 +154,8 @@ gz-sim

# Contributing

Please see
[CONTRIBUTING.md](https://github.com/gazebosim/gz-sim/blob/main/CONTRIBUTING.md).
Please see the
[contribution guide](https://gazebosim.org/docs/all/contributing/).

# Code of Conduct

Expand Down
4 changes: 2 additions & 2 deletions examples/plugin/custom_sensor_system/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ It uses the odometer created on this example:
From the root of the `gz-sim` repository, do the following to build the example:

~~~
cd examples/plugins/custom_sensor_system
cd examples/plugin/custom_sensor_system
mkdir build
cd build
cmake ..
Expand All @@ -27,7 +27,7 @@ the `odometer.sdf` file that's going to be loaded.
Before starting Gazebo, we must make sure it can find the plugin by doing:

~~~
cd examples/plugins/custom_sensor_system
cd examples/plugin/custom_sensor_system
export GZ_SIM_SYSTEM_PLUGIN_PATH=`pwd`/build
~~~

Expand Down
Empty file.
2 changes: 1 addition & 1 deletion examples/worlds/dem_monterey_bay.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
<property type="string" key="state">docked</property>
</gz-gui>

<engine>ogre</engine>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0 0 0</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
Expand Down
2 changes: 1 addition & 1 deletion examples/worlds/dem_moon.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
<property type="string" key="state">docked</property>
</gz-gui>

<engine>ogre</engine>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0 0 0</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
Expand Down
2 changes: 1 addition & 1 deletion examples/worlds/dem_volcano.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
<property type="string" key="state">docked</property>
</gz-gui>

<engine>ogre</engine>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0 0 0</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
Expand Down
4 changes: 4 additions & 0 deletions examples/worlds/empty_gui.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,10 @@ This example helps illustrate the interaction of the MinimalScene with other GUI

<world name="empty_gui">

<gz:policies>
<include_gui_default_plugins>false</include_gui_default_plugins>
</gz:policies>

<gui fullscreen="0">
<plugin filename="MinimalScene" name="3D View">
<gz-gui>
Expand Down
12 changes: 6 additions & 6 deletions examples/worlds/joint_trajectory_controller.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -479,21 +479,21 @@
<child>RR_velocity_control_link1</child>
<axis>
<xyz>1 0 0</xyz>
<dynamics>
<damping>0.02</damping>
</dynamics>
</axis>
<dynamics>
<damping>0.02</damping>
</dynamics>
</joint>
<joint name="RR_velocity_control_joint2" type="revolute">
<pose relative_to="RR_velocity_control_link1">0 0 0.1 0 0 0</pose>
<parent>RR_velocity_control_link1</parent>
<child>RR_velocity_control_link2</child>
<axis>
<xyz>1 0 0</xyz>
<dynamics>
<damping>0.01</damping>
</dynamics>
</axis>
<dynamics>
<damping>0.01</damping>
</dynamics>
</joint>
<!-- Controller -->
<plugin
Expand Down
73 changes: 73 additions & 0 deletions examples/worlds/shadow_texture_size.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
<?xml version="1.0" ?>
<sdf version="1.9">
<world name="default">
<scene>
<background>0.1 0.1 0.1</background>
<ambient>0.0 0.0 0.0</ambient>
</scene>

<!--GUI plugins-->
<gui>
<plugin filename="MinimalScene" name="3D View">
<engine>ogre2</engine>
<camera_pose>-10 0 7 0 0.5 0</camera_pose>
<shadows>
<texture_size light_type="directional">8192</texture_size>
</shadows>
</plugin>

<plugin filename="GzSceneManager" name="Scene Manager"/>
<plugin filename="InteractiveViewControl" name="Interactive view control"/>
</gui>

<!--lighting-->
<light type="directional" name="sun">
<pose>0 0 8 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0 0 0 0</specular>
<attenuation>
<range>50</range>
<constant>0</constant>
<linear>0</linear>
<quadratic>0</quadratic>
</attenuation>
<cast_shadows>true</cast_shadows>
<direction>-2 2 -1.5</direction>
<intensity>1.0</intensity>
</light>

<!--scene objects-->
<include>
<pose>0 0 0 0 0 -1.57</pose>
<uri>
https://fuel.gazebosim.org/1.0/OpenRobotics/models/Garden Mascot
</uri>
</include>

<model name="floor">
<pose>-5 0 -0.5 0 0 0</pose>
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>15 15 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>15 15 1</size>
</box>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>
17 changes: 16 additions & 1 deletion python/src/gz/sim/Joint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,22 @@ void defineSimJoint(py::object module)
py::arg("ecm"),
py::arg("limits"),
"Set the effort limits on a joint axis.")
.def("set_position_imits", &gz::sim::Joint::SetPositionLimits,
.def("set_position_imits",
[](pybind11::object &self, EntityComponentManager &_ecm,
const std::vector<math::Vector2d> &_limits)
{
auto warnings = pybind11::module::import("warnings");
auto builtins = pybind11::module::import("builtins");
warnings.attr("warn")(
"set_position_imits() is deprecated, use set_position_limits() instead.",
builtins.attr("DeprecationWarning"));

return self.attr("set_position_limits")(_ecm, _limits);
},
py::arg("ecm"),
py::arg("limits"),
"Set the position limits on a joint axis.")
.def("set_position_limits", &gz::sim::Joint::SetPositionLimits,
py::arg("ecm"),
py::arg("limits"),
"Set the position limits on a joint axis.")
Expand Down
Loading

0 comments on commit 4a833ac

Please sign in to comment.