diff --git a/README.md b/README.md index 8c35bb9549..2920bc856c 100644 --- a/README.md +++ b/README.md @@ -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) @@ -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. @@ -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 diff --git a/examples/plugin/custom_sensor_system/README.md b/examples/plugin/custom_sensor_system/README.md index 47700bc7fe..7d47ddb04b 100644 --- a/examples/plugin/custom_sensor_system/README.md +++ b/examples/plugin/custom_sensor_system/README.md @@ -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 .. @@ -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 ~~~ diff --git a/examples/worlds/actors_population.sdf b/examples/worlds/actors_population.sdf deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/examples/worlds/dem_monterey_bay.sdf b/examples/worlds/dem_monterey_bay.sdf index 7f2d170121..39539ca1f2 100644 --- a/examples/worlds/dem_monterey_bay.sdf +++ b/examples/worlds/dem_monterey_bay.sdf @@ -22,7 +22,7 @@ docked - ogre + ogre2 scene 0 0 0 0.8 0.8 0.8 diff --git a/examples/worlds/dem_moon.sdf b/examples/worlds/dem_moon.sdf index a1de71ad5e..047607d3f1 100644 --- a/examples/worlds/dem_moon.sdf +++ b/examples/worlds/dem_moon.sdf @@ -29,7 +29,7 @@ docked - ogre + ogre2 scene 0 0 0 0.8 0.8 0.8 diff --git a/examples/worlds/dem_volcano.sdf b/examples/worlds/dem_volcano.sdf index f48b2779a4..f2f766b869 100644 --- a/examples/worlds/dem_volcano.sdf +++ b/examples/worlds/dem_volcano.sdf @@ -21,7 +21,7 @@ docked - ogre + ogre2 scene 0 0 0 0.8 0.8 0.8 diff --git a/examples/worlds/empty_gui.sdf b/examples/worlds/empty_gui.sdf index 0975a4f142..54df8c2e31 100644 --- a/examples/worlds/empty_gui.sdf +++ b/examples/worlds/empty_gui.sdf @@ -37,6 +37,10 @@ This example helps illustrate the interaction of the MinimalScene with other GUI + + false + + diff --git a/examples/worlds/joint_trajectory_controller.sdf b/examples/worlds/joint_trajectory_controller.sdf index 2f9508bd49..d6b62a5b8c 100644 --- a/examples/worlds/joint_trajectory_controller.sdf +++ b/examples/worlds/joint_trajectory_controller.sdf @@ -479,10 +479,10 @@ RR_velocity_control_link1 1 0 0 + + 0.02 + - - 0.02 - 0 0 0.1 0 0 0 @@ -490,10 +490,10 @@ RR_velocity_control_link2 1 0 0 + + 0.01 + - - 0.01 - &_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.") diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index 1c45bfc4e8..2c258c1ad8 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -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" @@ -67,7 +68,7 @@ #include "gz/sim/components/NavSat.hh" #include "gz/sim/components/ParentEntity.hh" #include "gz/sim/components/ParentLinkName.hh" -#include +#include "gz/sim/components/ParticleEmitter.hh" #include "gz/sim/components/Performer.hh" #include "gz/sim/components/Physics.hh" #include "gz/sim/components/PhysicsEnginePlugin.hh" @@ -1004,9 +1005,27 @@ Entity SdfEntityCreator::CreateEntities(const sdf::ParticleEmitter *_emitter) // Entity Entity emitterEntity = this->dataPtr->ecm->CreateEntity(); + auto particleEmitterMsg = convert(*_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(*_emitter))); + components::ParticleEmitter(particleEmitterMsg)); this->dataPtr->ecm->CreateComponent(emitterEntity, components::Pose(ResolveSdfPose(_emitter->SemanticPose()))); this->dataPtr->ecm->CreateComponent(emitterEntity, diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index 4e75a68ea0..c3562a77fb 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -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 diff --git a/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.cc b/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.cc index d2b8f4c20c..cfab7f414f 100644 --- a/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.cc +++ b/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.cc @@ -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 @@ -194,11 +194,11 @@ 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 @@ -206,12 +206,13 @@ void GlobalIlluminationCiVct::LoadGlobalIlluminationCiVct() 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 @@ -225,6 +226,7 @@ void GlobalIlluminationCiVct::LoadGlobalIlluminationCiVct() << std::endl; gz::gui::App()->findChild()->removeEventFilter(this); + return false; } else { @@ -254,6 +256,7 @@ void GlobalIlluminationCiVct::LoadGlobalIlluminationCiVct() this->OnRefreshCamerasImpl(); } + return true; } /// \brief XML helper to retrieve values and handle errors @@ -358,9 +361,7 @@ void GlobalIlluminationCiVct::LoadConfig( const tinyxml2::XMLElement *_pluginElem) { if (this->title.empty()) - this->title = "Global Illumination (VCT)"; - - std::lock_guard lock(this->dataPtr->serviceMutex); + this->title = "Global Illumination (CI VCT)"; if (auto elem = _pluginElem->FirstChildElement("enabled")) { @@ -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 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 lock(this->dataPtr->serviceMutex); if (this->dataPtr->gi) { if (!this->dataPtr->visualDirty && !this->dataPtr->gi->Enabled() && @@ -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 diff --git a/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.hh b/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.hh index 6ebaee5741..d5327ae32f 100644 --- a/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.hh +++ b/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.hh @@ -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 diff --git a/src/gui/plugins/global_illumination_vct/GlobalIlluminationVct.cc b/src/gui/plugins/global_illumination_vct/GlobalIlluminationVct.cc index 0d6400c1a5..3abbabaec4 100644 --- a/src/gui/plugins/global_illumination_vct/GlobalIlluminationVct.cc +++ b/src/gui/plugins/global_illumination_vct/GlobalIlluminationVct.cc @@ -166,13 +166,13 @@ GlobalIlluminationVct::~GlobalIlluminationVct() } ///////////////////////////////////////////////// -void GlobalIlluminationVct::LoadGlobalIlluminationVct() +bool GlobalIlluminationVct::LoadGlobalIlluminationVct() REQUIRES(this->dataPtr->serviceMutex) { auto loadedEngNames = rendering::loadedEngines(); if (loadedEngNames.empty()) { - return; + return false; } // assume there is only one engine loaded @@ -188,11 +188,11 @@ void GlobalIlluminationVct::LoadGlobalIlluminationVct() { gzerr << "Internal error: failed to load engine [" << engineName << "]. GlobalIlluminationVct plugin won't work." << std::endl; - return; + return false; } if (engine->SceneCount() == 0) - return; + return false; // assume there is only one scene // load scene @@ -200,15 +200,16 @@ void GlobalIlluminationVct::LoadGlobalIlluminationVct() 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 lidar visual + // Create GI gzdbg << "Creating GlobalIlluminationVct" << std::endl; auto root = scene->RootVisual(); @@ -219,6 +220,7 @@ void GlobalIlluminationVct::LoadGlobalIlluminationVct() << std::endl; gz::gui::App()->findChild()->removeEventFilter(this); + return false; } else { @@ -228,6 +230,7 @@ void GlobalIlluminationVct::LoadGlobalIlluminationVct() this->dataPtr->scene = scene; this->dataPtr->initialized = true; } + return true; } /// \brief XML helper to retrieve values and handle errors @@ -319,8 +322,6 @@ void GlobalIlluminationVct::LoadConfig(const tinyxml2::XMLElement *_pluginElem) if (this->title.empty()) this->title = "Global Illumination (VCT)"; - std::lock_guard lock(this->dataPtr->serviceMutex); - if (auto elem = _pluginElem->FirstChildElement("enabled")) { GetXmlBool(elem, this->dataPtr->enabled); @@ -394,15 +395,35 @@ bool GlobalIlluminationVct::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 render thread, so it's safe to make // rendering calls here - std::lock_guard lock(this->dataPtr->serviceMutex); if (!this->dataPtr->initialized) { - this->LoadGlobalIlluminationVct(); + if (this->LoadGlobalIlluminationVct()) + { + // update properties and notify QML + this->SetEnabled(this->dataPtr->enabled); + this->SetResolutionX(this->dataPtr->resolution[0]); + this->SetResolutionY(this->dataPtr->resolution[1]); + this->SetResolutionZ(this->dataPtr->resolution[2]); + this->SetOctantCountX(this->dataPtr->octantCount[0]); + this->SetOctantCountY(this->dataPtr->octantCount[1]); + this->SetOctantCountZ(this->dataPtr->octantCount[2]); + this->SetBounceCount(this->dataPtr->bounceCount); + this->SetHighQuality(this->dataPtr->highQuality); + this->SetAnisotropic(this->dataPtr->anisotropic); + this->SetConserveMemory(this->dataPtr->conserveMemory); + this->SetThinWallCounter(this->dataPtr->thinWallCounter); + this->SetDebugVisualizationMode(this->dataPtr->debugVisMode); + this->EnabledChanged(); + this->LightingChanged(); + this->SettingsChanged(); + this->DebugVisualizationModeChanged(); + } } + std::lock_guard lock(this->dataPtr->serviceMutex); if (this->dataPtr->gi) { if (this->dataPtr->resetVisual) @@ -485,10 +506,6 @@ bool GlobalIlluminationVct::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->debugVisualizationDirty = false; } } - else - { - gzerr << "GI pointer is not set" << std::endl; - } } // Standard event processing diff --git a/src/gui/plugins/global_illumination_vct/GlobalIlluminationVct.hh b/src/gui/plugins/global_illumination_vct/GlobalIlluminationVct.hh index fde6a6979b..19a6d3ec61 100644 --- a/src/gui/plugins/global_illumination_vct/GlobalIlluminationVct.hh +++ b/src/gui/plugins/global_illumination_vct/GlobalIlluminationVct.hh @@ -156,7 +156,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 LoadGlobalIlluminationVct(); + /// \return True if GI VCT is loaded successfully, false otherwise. + public: bool LoadGlobalIlluminationVct(); /// \brief Set debug visualization mode GlogbalIllumination /// \param[in] _mode Index of selected debug visualization mode diff --git a/src/systems/follow_actor/FollowActor.cc b/src/systems/follow_actor/FollowActor.cc index 99d8315882..88f72c3f84 100644 --- a/src/systems/follow_actor/FollowActor.cc +++ b/src/systems/follow_actor/FollowActor.cc @@ -209,7 +209,9 @@ void FollowActor::PreUpdate(const UpdateInfo &_info, this->dataPtr->lastUpdate = _info.simTime; // Is there a follow target? - if (this->dataPtr->targetEntity == kNullEntity) + if (this->dataPtr->targetEntity == kNullEntity || + !_ecm.HasEntity(this->dataPtr->targetEntity) || + !_ecm.HasEntity(this->dataPtr->actorEntity)) return; // Current world pose diff --git a/src/systems/hydrodynamics/Hydrodynamics.cc b/src/systems/hydrodynamics/Hydrodynamics.cc index c3cd80e9c1..eed111deff 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.cc +++ b/src/systems/hydrodynamics/Hydrodynamics.cc @@ -355,21 +355,22 @@ void Hydrodynamics::Configure( prefix += snameConventionVel[j]; this->dataPtr->Ma(i, j) = SdfParamDouble(_sdf, prefix, 0); addedMassSpecified = (std::abs(this->dataPtr->Ma(i, j)) > 1e-6) - && addedMassSpecified; + || addedMassSpecified; } } _sdf->Get("disable_coriolis", this->dataPtr->disableCoriolis, false); - _sdf->Get("disable_added_mass", this->dataPtr->disableAddedMass, false); - if (!this->dataPtr->disableAddedMass || addedMassSpecified) + _sdf->Get("disable_added_mass", + this->dataPtr->disableAddedMass, false); + if (!this->dataPtr->disableAddedMass && addedMassSpecified) { - gzerr << "The use of added mass through this plugin is deprecated and will" - << "be removed in Gazebo J* as this formulation has instabilities." - << " We recommend using the SDF `` tag based method" + gzwarn << "The use of added mass through this plugin is deprecated and " + << "will be removed in Gazebo J* as this formulation has instabilities. " + << "We recommend using the SDF `` tag based method " << "[http://sdformat.org/spec?ver=1.11&elem=link" << "#inertial_fluid_added_mass]" - << "To get rid of this warning we recommend setting" - << "` to true." + << "To get rid of this warning we recommend setting " + << "`` to true and updating your model" << std::endl; } // Create model object, to access convenient functions diff --git a/src/systems/lens_flare/LensFlare.cc b/src/systems/lens_flare/LensFlare.cc index 8f099d6653..6739bb4e71 100644 --- a/src/systems/lens_flare/LensFlare.cc +++ b/src/systems/lens_flare/LensFlare.cc @@ -128,8 +128,9 @@ void LensFlare::Configure( } // Get Camera Name - this->dataPtr->cameraName = scopedName(this->dataPtr->entity, - _ecm, "::", false); + this->dataPtr->cameraName = + removeParentScope(scopedName(this->dataPtr->entity, + _ecm, "::", false), "::"); // call function that connects to post render event this->dataPtr->postRenderConn = diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc index f1d6d618fa..e2bf376e1e 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc @@ -530,6 +530,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) int contactSensorCounter = 0; sdf::Sensor depthCameraSdf; components::Pose depthCameraPose = components::Pose(); + std::string depthCameraTopic; for (const Entity &sensor : sensorsInsideLink) { if (_ecm.EntityHasComponentType(sensor, components::DepthCamera::typeId)) @@ -538,6 +539,10 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) depthCameraSdf = _ecm.Component(sensor)->Data(); depthCameraPose = *(_ecm.Component(sensor)); + auto depthCameraTopicComp = + _ecm.Component(sensor); + if (depthCameraTopicComp) + depthCameraTopic = depthCameraTopicComp->Data(); } if (_ecm.EntityHasComponentType(sensor, components::ContactSensor::typeId)) @@ -558,16 +563,6 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) } // Store depth camera update rate - if (!depthCameraSdf.Element()->HasElement("update_rate")) - { - if (!this->initErrorPrinted) - { - gzerr << "Depth camera should have an value " - << "(only printed once)" << std::endl; - this->initErrorPrinted = true; - } - return; - } this->cameraUpdateRate = depthCameraSdf.UpdateRate(); // Depth camera data is float, so convert Pose3d to Pose3f @@ -581,20 +576,27 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) depthCameraPose.Data().Rot().Z()); // Configure subscriber for depth camera images - if (!depthCameraSdf.Element()->HasElement("topic")) + if (depthCameraTopic.empty()) { - gzwarn << "Depth camera publishing to __default__ topic. " - << "It's possible that two depth cameras are publishing into the same " - << "topic" << std::endl; + // get the topic from sdf if the one in sensor topic component is empty + depthCameraTopic = depthCameraSdf.Topic(); } - else + + if (depthCameraTopic.empty()) { - gzdbg << "Depth camera publishing to " - << depthCameraSdf.Topic() << " topic" << std::endl; + if (!this->initErrorPrinted) + { + gzerr << "Depth camera topic is empty. " << std::endl; + this->initErrorPrinted = true; + } + return; } + gzdbg << "Depth camera publishing to " + << depthCameraTopic << " topic" << std::endl; + std::string topic = - "/" + depthCameraSdf.Topic() + "/points"; + "/" + depthCameraTopic + "/points"; if (!this->node.Subscribe(topic, &OpticalTactilePluginPrivate::DepthCameraCallback, this)) { diff --git a/test/worlds/joint_trajectory_controller.sdf b/test/worlds/joint_trajectory_controller.sdf index e761ab49b2..78ae047a68 100644 --- a/test/worlds/joint_trajectory_controller.sdf +++ b/test/worlds/joint_trajectory_controller.sdf @@ -324,10 +324,10 @@ RR_velocity_control_link1 1 0 0 + + 0.02 + - - 0.02 - 0 0 0.1 0 0 0 @@ -335,10 +335,10 @@ RR_velocity_control_link2 1 0 0 + + 0.01 + - - 0.01 - - + + true @@ -65,7 +65,7 @@ model. You can find more information on the [SDF website](http://sdformat.org/). - + 1 1 0.009948450858321252 @@ -73,7 +73,7 @@ model. You can find more information on the [SDF website](http://sdformat.org/). - + 0.08 0 0.05 0 0 0 diff --git a/tutorials/files/lander/lander_visuals.png b/tutorials/files/lander/lander_visuals.png index af12dd03a4..51b08228f2 100644 Binary files a/tutorials/files/lander/lander_visuals.png and b/tutorials/files/lander/lander_visuals.png differ diff --git a/tutorials/files/particle_emitter/particle_emitter_scatter_effects.sdf b/tutorials/files/particle_emitter/particle_emitter_scatter_effects.sdf new file mode 100644 index 0000000000..4a1c8e666b --- /dev/null +++ b/tutorials/files/particle_emitter/particle_emitter_scatter_effects.sdf @@ -0,0 +1,309 @@ + + + + + + + 0.001 + 1.0 + + + + ogre2 + + + + + + + + + RGB camera + floating + 350 + 315 + + camera + false + + + + Depth camera + floating + 350 + 315 + 500 + + depth_camera + false + + + + RGBD: image + floating + 350 + 315 + 320 + + rgbd_camera/image + false + + + + RGBD: depth + floating + 350 + 315 + 500 + 320 + + rgbd_camera/depth_image + false + + + + Thermal camera + floating + 350 + 315 + 500 + 640 + + thermal_camera + false + + + + + + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + https://fuel.gazebosim.org/1.0/openrobotics/models/fog generator + + + + 8 0 0.5 0 0.0 3.14 + + 0.05 0.05 0.05 0 0 0 + + 0.1 + + 0.000166667 + 0.000166667 + 0.000166667 + + + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + camera + + + + 10 + depth_camera + + 1.05 + + 320 + 240 + R_FLOAT32 + + + 0.1 + 100.0 + + + + + " + lidar + 10 + + + + 640 + 1 + -1.396263 + 1.396263 + + + 1 + 0.01 + 0 + 0 + + + + 0.08 + 10.0 + 0.01 + + + 1 + true + + + + true + + + + 8 0 0.5 0 0.0 3.14 + true + + 0.05 0.05 0.05 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + rgbd_camera + + + true + + + + 8 0 0.5 0 0.0 3.14 + true + + 0.05 0.05 0.05 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + thermal_camera + + + + + + 0 0 0 0 0 1.570796 + rescue_randy + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Rescue Randy + + + + diff --git a/tutorials/lander.md b/tutorials/lander.md index 184f17be44..3c1552ebfe 100644 --- a/tutorials/lander.md +++ b/tutorials/lander.md @@ -37,7 +37,7 @@ mkdir -p ~/gazebo_maritime/models/my_lander && cd ~/gazebo_maritime/models/my_la Download the `model.config` file and copy it within that directory: ```bash -wget https://raw.githubusercontent.com/gazebosim/gz-sim/gz-sim8/tutorials/files/lander/model.config -O ~/gazebo_maritime/models/my_lander/model.config +wget https://raw.githubusercontent.com/gazebosim/gz-sim/gz-sim9/tutorials/files/lander/model.config -O ~/gazebo_maritime/models/my_lander/model.config ``` In its simple version, the lander does not have any moving pieces, so the SDF @@ -95,7 +95,7 @@ Let's now add nicer-looking visuals to our lander. Download the following ```bash mkdir ~/gazebo_maritime/models/my_lander/meshes -wget https://raw.githubusercontent.com/gazebosim/gz-sim/gz-sim8/tutorials/files/lander/inkfish-lander.dae -O ~/gazebo_maritime/models/my_lander/meshes/inkfish-lander.dae +wget https://raw.githubusercontent.com/gazebosim/gz-sim/gz-sim9/tutorials/files/lander/inkfish-lander.dae -O ~/gazebo_maritime/models/my_lander/meshes/inkfish-lander.dae ``` Replace the `chassis_visual` element in your `model.sdf` with the following @@ -114,7 +114,7 @@ block: And launch Gazebo to see the results: ```bash -gz sim ~/my_models/my_lander/model.sdf +gz sim ~/gazebo_maritime/models/my_lander/model.sdf ``` Your box should now be replaced with a better looking mesh. @@ -153,7 +153,7 @@ Let's start with the world. Download the following world: ```bash mkdir -p ~/gazebo_maritime/worlds -wget https://raw.githubusercontent.com/gazebosim/gz-sim/gz-sim8/tutorials/files/lander/buoyant_lander.sdf -O ~/gazebo_maritime/worlds/buoyant_lander.sdf +wget https://raw.githubusercontent.com/gazebosim/gz-sim/gz-sim9/tutorials/files/lander/buoyant_lander.sdf -O ~/gazebo_maritime/worlds/buoyant_lander.sdf export GZ_SIM_RESOURCE_PATH=:$HOME/gazebo_maritime/models ``` diff --git a/tutorials/migration_plugins.md b/tutorials/migration_plugins.md index bad1919e6f..a134f796e8 100644 --- a/tutorials/migration_plugins.md +++ b/tutorials/migration_plugins.md @@ -1,7 +1,7 @@ \page migrationplugins Migration from Gazebo Classic: Plugins Gazebo Classic supports -[6 different C++ plugin types](http://gazebosim.org/tutorials?tut=plugins_hello_world&cat=write_plugin), +[6 different C++ plugin types](https://classic.gazebosim.org/tutorials?tut=plugins_hello_world#PluginTypes), each providing access to different parts of the API, like physics, rendering, sensors, GUI, etc. Due to Gazebo Sim's architecture based on an [ECS](https://en.wikipedia.org/wiki/Entity_component_system) diff --git a/tutorials/migration_sdf.md b/tutorials/migration_sdf.md index 37a6a444c0..a9ae0008db 100644 --- a/tutorials/migration_sdf.md +++ b/tutorials/migration_sdf.md @@ -250,7 +250,7 @@ side-by-side on the same file. Instead, keep separate files and inject the plugi needed. There isn't a built-in mechanism on SDFormat to inject plugins into files yet, -but users can make use of templating tools like [ERB](erb_template.html) +but users can make use of templating tools like [ERB](https://github.com/gazebosim/gz-sim/blob/gz-sim9/tutorials/erb_template.md) and [xacro](http://wiki.ros.org/xacro) to generate SDF files with the correct plugins. ### Default plugins @@ -260,8 +260,8 @@ For example, by default, Gazebo will load all the system plugins defined on the `~/.gz/sim/<#>/server.config` file and all GUI plugins defined on the `~/.gz/sim/<#>/gui.config` file. But the user can always remove plugins from those files, or choose different ones by adding `` tags to the SDF file. -(For more details, see the [Server configuration tutorial](server_config.html) -and the [GUI configuration tutorial](gui_config.html)). +(For more details, see the [Server configuration tutorial](https://github.com/gazebosim/gz-sim/blob/gz-sim9/tutorials/server_config.md) +and the [GUI configuration tutorial](https://github.com/gazebosim/gz-sim/blob/gz-sim9/tutorials/gui_config.md)). This is important to keep in mind when migrating your SDF files, because files that worked on Gazebo classic may need more plugins on Gazebo. diff --git a/tutorials/model_photo_shoot.md b/tutorials/model_photo_shoot.md index f3ce372c9c..0730e337a1 100644 --- a/tutorials/model_photo_shoot.md +++ b/tutorials/model_photo_shoot.md @@ -37,7 +37,7 @@ contains a good example of the different options and other related plugins: filename="gz-sim-sensors-system" name="gz::sim::systems::Sensors"> ogre2 - 1, 1, 1 + 1.0, 1.0, 1.0 ``` A render plugin is needed to render the image. If `ogre2` is used, as shown in @@ -53,7 +53,7 @@ contains a good example of the different options and other related plugins: filename="gz-sim-model-photo-shoot-system" name="gz::sim::systems::ModelPhotoShoot"> poses.txt - true + false ``` diff --git a/tutorials/move_camera_to_model.md b/tutorials/move_camera_to_model.md index 0ba5287eeb..8b6eac8172 100644 --- a/tutorials/move_camera_to_model.md +++ b/tutorials/move_camera_to_model.md @@ -7,7 +7,7 @@ This tutorial gives an introduction to Gazebo's service `/gui/move_to/model`. Th 1. Load the **View Angle** plugin. This service is only available when the **View Angle** plugin is loaded. 2. Call the service using the request message type `gz.msgs.GUICamera` and the response message type `gz.msgs.Boolean`. The distance to the object is defined as the z coordinate, and the direction of the camera with a quaternion. It's possible to select the projection type. -For example, Let's move the camera to the `box` model looking down from 5 meters away. +For example, Let's move the camera to the `box` model looking down from 5 meters away. This example uses the `shapes.sdf` world. ```bash gz service -s /gui/move_to/model --reqtype gz.msgs.GUICamera --reptype gz.msgs.Boolean -r 'name: "box", pose: {position: {z:5}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000 diff --git a/tutorials/particle_tutorial.md b/tutorials/particle_tutorial.md index c0c37e73b5..7150027684 100644 --- a/tutorials/particle_tutorial.md +++ b/tutorials/particle_tutorial.md @@ -97,7 +97,18 @@ The particles are not only a visual effect in simulation, they also have an effe * `gpu_lidar`: The particles have a scattering effect on the lidar range readings. * `thermal_camera`: The particles are not visible in the thermal camera image. -The gif below shows an [example world](https://gist.github.com/iche033/bcd3b7d3f4874e1e707e392d6dbb0aa0) with six different sensors looking at the fog generator with a rescue randy model inside the fog. + +The [particle_emitter_scatter_effects.sdf](https://github.com/gazebosim/gz-sim/blob/gz-sim9/tutorials/files/particle_emitter/particle_emitter_scatter_effects.sdf) +demo world shows six different sensors looking at the fog generator with a rescue randy model inside the fog. + +Download the example world file and launch it to see what it looks like. + +```bash +gz sim -v 4 -r particle_emitter_scatter_effects.sdf +``` + +Navigate to the Visualize Lidar plugin on the right and click on the refresh button to set the lidar topic. You should see the sensor images and lidar visualization like below: + @image html files/particle_emitter/sensor_scatter_tutorial.gif diff --git a/tutorials/video_recorder.md b/tutorials/video_recorder.md index efea6422c2..fa655c9b1a 100644 --- a/tutorials/video_recorder.md +++ b/tutorials/video_recorder.md @@ -13,7 +13,7 @@ Gazebo that already has this plugin included in the GUI. gz sim -v 4 video_record_dbl_pendulum.sdf ``` -In this demo world, you should see a video recorder icon positioned on the top. +In this demo world, you should see a video recorder icon positioned on the top left area of the window along with other buttons. Clicking on the video recorder button gives you the video format options that are available. @@ -107,5 +107,5 @@ generated video. The default bitrate is 2Mbps. Since Gazebo Common 3.10.2, there is support for utilizing the power of GPUs to speed up the video encoding process. See the -[Hardware-accelerated Video Encoding tutorial](https://gazebosim.org/api/common/5/hw-encoding.html) +[Hardware-accelerated Video Encoding tutorial](https://gazebosim.org/api/common/6/hw-encoding.html) for more details.