Skip to content

Commit

Permalink
Merge branch 'gz-sim9' into arjo/fix/restore_playback
Browse files Browse the repository at this point in the history
  • Loading branch information
arjo129 authored Sep 6, 2024
2 parents e77bf77 + 518cc31 commit 70fac2c
Show file tree
Hide file tree
Showing 30 changed files with 503 additions and 109 deletions.
10 changes: 5 additions & 5 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 @@ -154,7 +154,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 +163,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
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
23 changes: 21 additions & 2 deletions src/SdfEntityCreator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

#include "gz/sim/Events.hh"
#include "gz/sim/SdfEntityCreator.hh"
#include "gz/sim/Util.hh"

#include "gz/sim/components/Actor.hh"
#include "gz/sim/components/AirPressureSensor.hh"
Expand Down Expand Up @@ -67,7 +68,7 @@
#include "gz/sim/components/NavSat.hh"
#include "gz/sim/components/ParentEntity.hh"
#include "gz/sim/components/ParentLinkName.hh"
#include <gz/sim/components/ParticleEmitter.hh>
#include "gz/sim/components/ParticleEmitter.hh"
#include "gz/sim/components/Performer.hh"
#include "gz/sim/components/Physics.hh"
#include "gz/sim/components/PhysicsEnginePlugin.hh"
Expand Down Expand Up @@ -1004,9 +1005,27 @@ Entity SdfEntityCreator::CreateEntities(const sdf::ParticleEmitter *_emitter)
// Entity
Entity emitterEntity = this->dataPtr->ecm->CreateEntity();

auto particleEmitterMsg = convert<msgs::ParticleEmitter>(*_emitter);

// Update image path
// Ideally this is done by gz/sim/src/SceneManager.cc when creating
// the particle emitter. However the component stores a msg instead of
// an sdf so the sdf FilePath information is lost and rendering is not
// able to construct the full path of the image.
// \todo(iche033) Consider changing the ParticleEmitter component to
// store an sdf::ParticleEmitter object instead of msgs::ParticleEmitter.
std::string imagePath = _emitter->ColorRangeImage();
if (!imagePath.empty())
{
std::string path = common::findFile(asFullPath(imagePath,
_emitter->Element()->FilePath()));
path = path.empty() ? imagePath : path;
particleEmitterMsg.mutable_color_range_image()->set_data(path);
}

// Components
this->dataPtr->ecm->CreateComponent(emitterEntity,
components::ParticleEmitter(convert<msgs::ParticleEmitter>(*_emitter)));
components::ParticleEmitter(particleEmitterMsg));
this->dataPtr->ecm->CreateComponent(emitterEntity,
components::Pose(ResolveSdfPose(_emitter->SemanticPose())));
this->dataPtr->ecm->CreateComponent(emitterEntity,
Expand Down
6 changes: 5 additions & 1 deletion src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -168,9 +168,13 @@ class gz::sim::ServerConfigPrivate

this->timestamp = GZ_SYSTEM_TIME();

std::string timeInIso = common::timeToIso(this->timestamp);
#ifdef _WIN32
std::replace(timeInIso.begin(), timeInIso.end(), ':', '-');
#endif
// Set a default log record path
this->logRecordPath = common::joinPaths(home,
".gz", "sim", "log", common::timeToIso(this->timestamp));
".gz", "sim", "log", timeInIso);

// If directory already exists, do not overwrite. This could potentially
// happen if multiple simulation instances are started in rapid
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,13 +172,13 @@ GlobalIlluminationCiVct::~GlobalIlluminationCiVct()
}

/////////////////////////////////////////////////
void GlobalIlluminationCiVct::LoadGlobalIlluminationCiVct()
bool GlobalIlluminationCiVct::LoadGlobalIlluminationCiVct()
REQUIRES(this->dataPtr->serviceMutex)
{
auto loadedEngNames = rendering::loadedEngines();
if (loadedEngNames.empty())
{
return;
return false;
}

// assume there is only one engine loaded
Expand All @@ -194,24 +194,25 @@ void GlobalIlluminationCiVct::LoadGlobalIlluminationCiVct()
{
gzerr << "Internal error: failed to load engine [" << engineName
<< "]. GlobalIlluminationCiVct plugin won't work." << std::endl;
return;
return false;
}

if (engine->SceneCount() == 0)
return;
return false;

// assume there is only one scene
// load scene
auto scene = engine->SceneByIndex(0);
if (!scene)
{
gzerr << "Internal error: scene is null." << std::endl;
return;
return false;
}

if (!scene->IsInitialized() || scene->VisualCount() == 0)
if (!scene->IsInitialized() || scene->VisualCount() == 0 ||
scene->LightCount() == 0)
{
return;
return false;
}

// Create visual
Expand All @@ -225,6 +226,7 @@ void GlobalIlluminationCiVct::LoadGlobalIlluminationCiVct()
<< std::endl;

gz::gui::App()->findChild<gz::gui::MainWindow *>()->removeEventFilter(this);
return false;
}
else
{
Expand Down Expand Up @@ -254,6 +256,7 @@ void GlobalIlluminationCiVct::LoadGlobalIlluminationCiVct()

this->OnRefreshCamerasImpl();
}
return true;
}

/// \brief XML helper to retrieve values and handle errors
Expand Down Expand Up @@ -358,9 +361,7 @@ void GlobalIlluminationCiVct::LoadConfig(
const tinyxml2::XMLElement *_pluginElem)
{
if (this->title.empty())
this->title = "Global Illumination (VCT)";

std::lock_guard<std::mutex> lock(this->dataPtr->serviceMutex);
this->title = "Global Illumination (CI VCT)";

if (auto elem = _pluginElem->FirstChildElement("enabled"))
{
Expand Down Expand Up @@ -447,15 +448,25 @@ bool GlobalIlluminationCiVct::eventFilter(QObject *_obj, QEvent *_event)
{
if (_event->type() == gz::gui::events::Render::kType)
{
// This event is called in Scene3d's RenderThread, so it's safe to make
// This event is called in the render thread, so it's safe to make
// rendering calls here

std::lock_guard<std::mutex> lock(this->dataPtr->serviceMutex);
if (!this->dataPtr->initialized)
{
this->LoadGlobalIlluminationCiVct();
if (this->LoadGlobalIlluminationCiVct())
{
this->SetEnabled(this->dataPtr->enabled);
this->SetBounceCount(this->dataPtr->bounceCount);
this->SetHighQuality(this->dataPtr->highQuality);
this->SetAnisotropic(this->dataPtr->anisotropic);
this->SetDebugVisualizationMode(this->dataPtr->debugVisMode);
this->EnabledChanged();
this->LightingChanged();
this->DebugVisualizationModeChanged();
}
}

std::lock_guard<std::mutex> lock(this->dataPtr->serviceMutex);
if (this->dataPtr->gi)
{
if (!this->dataPtr->visualDirty && !this->dataPtr->gi->Enabled() &&
Expand Down Expand Up @@ -563,10 +574,6 @@ bool GlobalIlluminationCiVct::eventFilter(QObject *_obj, QEvent *_event)
this->dataPtr->resetRequested = false;
}
}
else
{
gzerr << "GI pointer is not set" << std::endl;
}
}

// Standard event processing
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,8 @@ inline namespace GZ_SIM_VERSION_NAMESPACE
public: bool eventFilter(QObject *_obj, QEvent *_event) override;

/// \brief Load the scene and attach LidarVisual to the scene
public: void LoadGlobalIlluminationCiVct();
/// \return True if GI CIVCT is loaded successfully, false otherwise.
public: bool LoadGlobalIlluminationCiVct();

/// \brief Set debug visualization mode GlogbalIllumination
/// \param[in] _mode Index of selected debug visualization mode
Expand Down
Loading

0 comments on commit 70fac2c

Please sign in to comment.