sim#
Gazebo Sim : A Robotic Simulator
Maintainer: michael AT openrobotics DOT org
Gazebo Sim is an open source robotics simulator. Through Gazebo Sim, users have access to high fidelity physics, rendering, and sensor models. Additionally, users and developers have multiple points of entry to simulation including a graphical user interface, plugins, and asynchronous message passing and services.
Gazebo Sim is derived from Gazebo Classic and represents over 16 years of development and experience in robotics and simulation. This library is part of the Gazebo project.
Table of Contents
Features
Dynamics simulation: Access multiple high-performance physics engines through Gazebo Physics.
Advanced 3D graphics: Through Gazebo Rendering, it’s possible to use rendering engines such as OGRE v2 for realistic rendering of environments with high-quality lighting, shadows, and textures.
Sensors and noise models: Generate sensor data, optionally with noise, from laser range finders, 2D/3D cameras, Kinect style sensors, contact sensors, force-torque, IMU, GPS, and more, all powered by Gazebo Sensors
Plugins: Develop custom plugins for robot, sensor, and environment control.
Graphical interface: Create, introspect and interact with your simulations through plugin-based graphical interfaces powered by Gazebo GUI.
Simulation models: Access numerous robots including PR2, Pioneer2 DX, iRobot Create, and TurtleBot, and construct environments using other physically accurate models available through Gazebo Fuel. You can also build a new model using SDF.
TCP/IP Transport: Run simulation on remote servers and interface to Gazebo Sim through socket-based message passing using Gazebo Transport.
Command line tools: Extensive command line tools for increased simulation introspection and control.
Install
See the installation tutorial.
Usage
Gazebo Sim can be run from the command line, once installed, using:
gz sim
For help, and command line options use:
gz sim -h
Known issue of command line tools
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 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:$HOME/ws/install/share/gz
where $HOME/ws
is an example colcon workspace used to build Gazebo.
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
See the installation tutorial.
Testing
See the installation tutorial.
See the Writing Tests section of the contributor guide for help creating or modifying tests.
Folder Structure
Refer to the following table for information about important directories and files in this repository.
gz-sim
├── examples Various examples that can be run against binary or source installs of gz-sim.
│ ├── plugin Example plugins.
│ ├── standalone Example standalone programs that use gz-sim as a library.
│ └── worlds Example SDF world files.
├── include/gz/sim Header files that downstream users are expected to use.
│ └── detail Header files that are not intended for downstream use, mainly template implementations.
├── python Python wrappers
├── src Source files and unit tests.
│ ├── gui Graphical interface source code.
│ └── systems System source code.
├── test
│ ├── integration Integration tests.
│ ├── performance Performance tests.
│ ├── plugins Plugins used in tests.
│ ├── regression Regression tests.
├── tutorials Tutorials, written in markdown.
├── Changelog.md Changelog.
├── CMakeLists.txt CMake build script.
├── Migration.md Migration guide.
└── README.md This readme.
Contributing
Please see the contribution guide.
Code of Conduct
Please see CODE_OF_CONDUCT.md.
Versioning
This library uses Semantic Versioning. Additionally, this library is part of the Gazebo project which periodically releases a versioned set of compatible and complimentary libraries. See the Gazebo website for version and release information.
License
This library is licensed under Apache 2.0. See also the LICENSE file.
Gazebo Sim 9.x
Gazebo Sim 9.0.0 (2024-09-25)
Baseline: this includes all changes from 8.6.0 and earlier.
Miscellaneous documentation fixes
Fix log playback GUI display
Add tutorial + example SDF for shadow texture size
Fix making breadcrumb static if it’s a nested model
Update physics system error msg when plugin can not be loaded
Fix configuring global illumination GUI plugin parameters
Fix particle emitter color range image path warning
Fix empty gui world file
Fix crash on windows due to invalid log directory path
Use ogre2 for DEM worlds
Fix crash when running the optical tactile sensor world
Prevent follow actor plugin from crashing when actor is removed
Fix hydrodynamics deprecation warning.
Removed actor population world due to bad merge
Fixed warning joint trayectory sdf
Fix looking up camera name in camera lens system
Add a flexible mechanism to combine user and default plugins
Fix crash at exit due to a race condition with new signal handler
Remove gz:system_priority/ from test worlds
Consolidate entity creation.
Add cmake install prefix
Fix UNIT_Server_TEST failure caused by change in behavior of
gz::common::SignalHandler
Fix SphericalCoordinates deprecation warnings
Revert behavior change introduced in #2452
Specify System::PreUpdate, Update execution order
Add System interface to set default priority
Force Qt to use xcb plugin on Wayland
Physics: set link velocity from VelocityReset components
ForceTorque system: write WrenchMeasured to ECM
Remove unused var
Deprecate use of added mass via hydrodynamics
Make sure steering joints exist before updating velocity / odometry in AckermannSteering plugin
Fix ResourceSpawner
gui_system_plugin: clarify description in README
Fix adding system to non-existent entity
Remove ignition related deprecations
Fix #2458 - Checking linkEnity is empty
Specify System::PreUpdate, Update execution order
Improve signal handling
Initialize threadsNeedCleanUp
Added support for spacecraft thrusters
Remove systems if their parent entity is removed
Disable rendering tests that are failing on github actions
Fix warnings generated by NetworkConfigTest
Support visualizing mesh collisions with convex decomposition
Remove python3-distutils from package.xml
shapes.sdf example: bump to 1.12, add cone shape
Adding cone primitives.
Enable 24.04 CI, require cmake 3.22.1
Parse and set bullet solver iterations
ForceTorque system: improve readability
Fix warn unused variable in test
Physics: remove VelocityCmd at each time step
Regroup tutorials into four categories
Remove HIDE_SYMBOLS_BY_DEFAULT: replace by a default configuration in gz-cmake.
Enable HIDE_SYMBOLS_BY_DEFAULT + linux patches * Pull request #2248
Use sdf FindElement API to avoid const_cast
Bumps in Ionic: gz-sim9
Gazebo Sim 8.x
Gazebo Sim 8.6.0 (2024-07-25)
Fix error resolving gazebo classic material when loading world
Remove systems if their parent entity is removed
Fix warnings generated by NetworkConfigTest
Fix lidar visualization when
gz_frame_id
is specifiedBackport convex decomposition visualization
Add UserCommands plugin to GPU lidar sensor example
Check if any entity actually has a ContactSensorData component before calling GetContactsFromLastStep
Enable tests on macOS
Update description of reset_sensors test
Magnetometer: correct field calculation
Address a couple of todos in Conversion.cc
Correct name of sensor in warning message
Set max contacts for collision pairs
Add GravityEnabled boolean component
Add support for no gravity link
Handle sdf::Geometry::EMPTY in conversions
Use topicFromScopedName in a few systems
Fix typo in a comment
Gazebo Sim 8.5.0 (2024-06-26)
Backport: Adding cone primitives
Permit to run gz sim -g on Windows
Parse voxel resolution SDF param when decomposing meshes
Fix model command api test
Add tutorial for using the Pose component
Do not update sensors if it a triggered sensor
Gazebo Sim 8.4.0 (2024-06-12)
Add pause run tutorial
Fix warning message to show precise jump back in time duration
Optimize rendering sensor pose updates
Remove a few extra zeros from some sdf files
Use VERSION_GREATER_EQUAL in cmake logic
Support mesh optimization when using AttachMeshShapeFeature
Rephrase cmake comment about CMP0077
Fix CMake warnings in Noble
Update sensors with pending trigger immediately in Sensors system
Add missing algorithm include
Add Track and Follow options in gui EntityContextMenu
ForceTorque system: improve readability
LTA Dynamics System
Remove Empty Test File
Fix GCC/CMake warnings for Noble
Fix warn unused variable in test
Fix name of gz-fuel_tools in package.xml
Add package.xml
Fix namespace and class links in documentation references that use namespace
gz
Fix ModelPhotoShootTest test failures
Enable StoreResolvedURIs when loading SDF
Drop python3-disttutils from apt packages files
Added example world for
DopplerVelocityLogSystem
Fix Gazebo/White and refactored MaterialParser
Support for Gazebo materials
Gazebo Sim 8.3.0 (2024-04-11)
Use relative install paths for plugin shared libraries and gz-tools data
Use
steer_p_gain
for UpdateVelocity steer joint speedFix TriggeredPublisher test
Use SetComponentData to simplify code and improve coverage
Remove unnecessary sleep
Fixed undefined behavior in thruster.cc
Added mutex to protect stored time variables
Fixed turning error in ackermann steering
Check null mesh
Publish step size in world stats topic
Gazebo Sim 8.2.0 (2024-03-14)
Add reference to joint_controller.md tutorial.
Fix wget in maritime tutorials
Add entity and sdf parameters to Server’s AddSystem interface
Add entity validation to OdometryPublisher
Fix typo in Joint.hh
Gazebo Sim 8.1.0 (2024-02-06)
Add tutorial for using components in systems
Light entity match SDF boolean for UserCommands.
Explicitly check SKIP_PYBIND11 for python bindings
Fix
INTEGRATION_save_world
on windowsChange an entities visual material color by topic.
Fix ModelPhotoShootTest test failures
Support for Gazebo materials
Added tutorial for Gazebo joint controller plugin
Lift Drag Bug Fix
Fix URL in hydrodynamics tutorial
Install the Python libs to system site-packages instead of root
Maritime tutorials 💧
Update CI badges in README
Fix incorrect light direction in tunnel.sdf example
Allow removal of model that has joint_position_controller plugin.
Fix DLL linkage/visibility issues
mecanum_drive
: use mesh wheels in example worldDisable distortion camera test on Linux
environment_preload
: fix windows compiler warningsEnvironmentPreload: ignerr -> gzerr
Update friction parameters for skid steer example
Fixed Centre of Mass and Inertia Matrix Calculation Bug
MeshInertiaCalculator::CalculateMassProperties()
functionBackport #2231: Use sdf FindElement API to avoid
const_cast
Add libpython3-dev CI dependency
Standardize Doxygen parameter formatting for systems
Use
GZ_PI
instead ofM_PI
to fix windows buildsAdd note about elevator example
Porting Advanced Lift Drag Plugin to Gazebo
Fix for sensor pointer null when navsat plugin in included in sdf
Implements a method to get the link inertia
Fix sensors system parallel updates
Fix custom_sensor_system example
Relax pose check in actor no mesh test
backport component inspector Vector3d width fix
fix INTEGRATION_save_world’s SdfGeneratorFixture.ModelWithNestedIncludes test
Support specifying the name of light associated with lens flares
Bump Fuel model version in test
Fix environment system loading mechanism
Infrastructure
Gazebo Sim 8.0.0 (2023-09-29)
TouchPlugin: Reset the plugin with the initial values
Fix another deadlock in sensors system
Documentation fixes
Fix Examples
Load transform control and select entities plugins in thermal camera world
Fixed invalid service names
Add automatic moment of inertia calculation for meshes
ign -> gz
Adds python demo examples
Add support for writing systems in Python
Apply mimic constraint to joints (only Bullet-featherstone)
Fix rendering tests
Make systems and tests include headers they use
Adds Python bindings for the Actor, Joint, Light, Link, Model, Sensor, World convenience class
Add version number to gz.common python binding
Infrastructure
Bumps in harmonic : sdformat14, gz-physics6, gz-sensors8, gz-gui8, gz-rendering8, gz-transport13, gz-msgs10, gz-fuel-tools9
Use new sky cubemap, instead of header
Remove deprecations and address some todos for Harmonic
Use ogre2 in wide angle camera and lens flares worlds
Use new API for creating projector
Fix const-correctness of the
Model::JointByName
andModel::LinkByName
APIsChange type of
Component::typeName
and address outstanding todosAdd Lens Flare System
Fix TopicInfo deprecation warnings in Harmonic
Add DopplerVelocityLogSystem plugin
GUI for Global Illumination (VCT / CI VCT)
Add CLI to switch to Vulkan & Metal backends
Remove deprecations for main/gz-sim8
Acoustic comms plugin
Set seed value using CLI
⬆️ Bump main to 8.0.0~pre1
Gazebo Sim 7.x
Gazebo Sim 7.8.0 (2024-07-22)
Added support for spacecraft thrusters
Disable rendering tests that are failing on github actions
Consolidate entity creation.
Set max contacts for collision pairs
Add GravityEnabled boolean component
Add support for no gravity link
Handle sdf::Geometry::EMPTY in conversions
Use topicFromScopedName in a few systems
Fix typo in a comment
Remove a few extra zeros from some sdf files
Use VERSION_GREATER_EQUAL in cmake logic
Rephrase cmake comment about CMP0077
ForceTorque system: improve readability
LTA Dynamics System
Fix namespace and class links in documentation references that use namespace
gz
Fix ModelPhotoShootTest test failures
update sdf version
Fix Gazebo/White and refactored MaterialParser
Support for Gazebo materials
Gazebo Sim 7.7.0 (2024-01-17)
Allow using plugin file names and environment variables compatible with Garden and later
Added tutorial for Gazebo joint controller plugin
Fix incorrect light direction in tunnel.sdf example
Fix DLL linkage/visibility issues
mecanum_drive: use mesh wheels in example world
environment_preload: fix windows compiler warnings
EnvironmentPreload: ignerr -> gzerr
Update friction parameters for skid steer example
Use sdf FindElement API to avoid const_cast
Use
GZ_PI
instead ofM_PI
to fix windows buildsAdd note about elevator example
Porting Advanced Lift Drag Plugin to Gazebo
Fix macOS test failures by registering components in the core library
Fix for sensor pointer null when navsat plugin in included in sdf
Fix another deadlock in sensors system
Fix sensors system parallel updates
Relax pose check in actor no mesh test
backport component inspector Vector3d width fix
fix INTEGRATION_save_world’s SdfGeneratorFixture.ModelWithNestedIncludes test
Lift Drag Bug Fix
Bump Fuel model version in test
Fix enviroment system loading mechanism
Infrastructure
Gazebo Sim 7.6.0 (2023-09-26)
Documentation updates
Backport reset button fix
Fix SDFormat xml output of sdf_exporter
Fix duplicate entries in joint position controller GUI plugin
Use default physics engine in example worlds
Fix move to model
Remove GZ_PHYSICS_ENGINE_INSTALL_DIR deprecation warnings
Remove forward-ported restriction on model loading
Odometry topic for the track controller system
Add tutorials for ApplyForceTorque and MouseDrag plugins
Prevent crash when viewing heightmap collision
Force offset and vector magnitude support in ApplyForceTorque
Fix plugin conversion error message
Visualization tools for the ApplyForceTorque GUI plugin
Improve documentation on how to replace Scene3D plugin
Configurable stiffnesses in MouseDrag
Infrastructure
Add new MouseDrag plugin
Relax scene init check in visualize lidar gui plugin
Add force offset support to ApplyLinkWrench system and to Link API
Proposal to add deadband to thruster
Avoid nullptr dereference if TouchPlugin is not attached to a model entity.
Remove unnecessary headers to fix ABI checker
Fix Joint Position Controller Behaviour Described in #1997
Include contact force, normal, and depth in contact message
Use sdf::Element::FindElement instead of GetElement in ApplyLinkWrench
Backport sensors system threading optimization changes
Apply Force and Torque GUI plugin
Adds a warning if the
Server
method of aTestFixture
is called beforeFinalize
Support loading mesh by mesh name in
<mesh><uri>
ComponentInspector: display PhysicsEnginePlugin
Send BlockOrbit false events only once from TransformControl plugin
Categorize tutorials list
Add time out to wait to avoid deadlock
Add optional binary relocatability
Several minor fixes
Protobuf: Do not require version 3 do support Protobuf 4.23.2 (23.2)
Support world joints (joints inside
<world>
tags)Disable pybind11 on Windows by default
Port record topic fix
Allow re-attaching detached joint
Enable GzWeb visualization of markers by republishing service requests on a topic
Support loading Projectors
Small fixes to gz headers
Speed up Resource Spawner load time by fetching model list asynchronously
Add redirection header gz/sim.hh
Add missing cmake exports from core library
Add tutorial on migrating the Sensor class from gazebo classic
ign -> gz Migrate Ignition Headers : gz-sim
Gazebo Sim 7.5.0 (2023-05-14)
Actuators message input for JointController.
fixed a code block in the python interfaces tutorial
Add missing cmake exports from core library
Actuators message for JointPositionController.
Update sdf plugins to use actuator_number.
Unload render engine when the sensors system exits
Use GzSpinBox.
Add tutorial on migrating the Actor class from gazebo classic
Add back in the marker example
Optimize render updates and use of thread mutexes in Sensors system
Fix use of actors that only has trajectory animation
Actuators message input for Ackermann Steering.
Add tutorial on migrating the Joint class from gazebo classic
Add tutorial on migrating the Light class from gazebo classic
Remove filtering from realtime factor (RTF) calculation
Fix docker/README.md
gz_TEST: improve initial sim time test reliability
Use a queue to track component registration from mulitiple sources
Initialize services in ViewAngle constructor
CI workflow: use checkout v3
Rename COPYING to LICENSE
add comment on center of buoyancy force
Get Windows to green on gz-sim7
Add Light class
Resolve inconsistent visibility on ign-gazebo6
relax msg count check in RF comms integration test
Fix off-by-one error in physics test
Fix formatting of error messages with large mesh file names
Add Actor class
Update all velocity and acceleration components of non-link entities
Add Sensor class
Minor vocab fix
Allow to change camera user hfov in camera_view plugin
Address a few Windows CI Issues
Added magnetometer value based on location
Allow specifying initial simulation time with a CLI argument
Add Joint class
Added reset simulation tutorial
Add SensorTopic component to rendering sensors
Use a queue to track component registration from mulitiple sources
Document behaviour changes introduced #1784
Fix GUI_clean_exit test by increasing thread delay
Partial backport of 1728
Fix gz plugin paths in windows
Increase timeout for UNIT_Gui_clean_exit_TEST
fix triggered camera test by waiting for rendering / scene to be ready
cmdsim.rb: fix ruby syntax
Fix some windows warnings (C4244 and C4305)
Minor optimization to transform control tool
inherit material cast shadows property
fix record topic
Remove duplicate Fuel server used by ResourceSpawner
re-add namespace
Fix QML warnings regarding binding loops
Update documentation on
UpdateInfo::realTime
Add jennuine as GUI codeowner
remove PlotIcon
Final update of ignitionrobotics to gazebosim for citadel
Convert ignitionrobotics to gazebosim in tutorials
Convert ignitionrobotics to gazebosim in sources and includes
Convert ignitionrobotics to gazebosim in tests directory
Added collection name to About Dialog
Citadel: Removed warnings
Remove actors from screen when they are supposed to
readd namespaces for Q_ARGS
🎈 3.14.0
Remove redundant namespace references
🎈 3.14.0~pre1
Gazebo Sim 7.4.0 (2023-02-14)
Added airspeed sensor
JointPosController: support nested joints
cmdsim.rb: fix ruby syntax
Fix view angle plugin
Fix cmake unrecognized argument warning
Gazebo Sim 7.3.0 (2023-02-02)
Fluid added mass
Add P gain value for Ackermann steering.
Add orientation to Odom with covariance.
Gazebo Sim 7.2.0 (2023-01-25)
Enable the JointController and JointPositionController to use sub_topics and control multiple joints.
Ackermann steering with steering angle and sub_topic.
port: 6 to 7 (10-JAN-2023)
Add ignition alias back
fix SdfGenerator unit test
Allow using a CSV file to define currents for hydrodynamic system
Add multichannel lookup for environment sensors.
Example controller for LRAUV
Fix component removal in component inspector
port: 6 to 7 (06-DEC-2023)
port: 6 to 7 (29-NOV-2023)
Fix #1812.
Removed unused attributes
Fixes buoyancy flakiness when spawning entities
Remove fixed width from world control
Backport #1748: Adds a tool for environment data visualization and custom environmental sensors
Acoustic comms : Propagation model
Add pre-commit hooks configuration
Add checkbox in view angle plugin for toggling view control reference visual
Add EnvironmentalData component
Gazebo Sim 7.1.0 (2022-11-10)
Allow SDF model to be constructed in a single shot
Allow loading a model SDF file in the Server class
Address flaky UNIT_Gui_TEST
Change name of nameFilter of saveDialog to “SDF files”
Acoustic comms : Packet collision timeout
Fix typo in include inside Export.hh
Towards Green CI
Refactor: Trajectory loading seperated into external function
Add pybind11 module as MODULE
Clarify errors when plugins fail to load
Fix tutorial for
blender_sdf_exporter
Cherry pick acoustic comms to gz-sim7
Update tutorial for
blender_distort_meshes
Removes Actor Visuals When They Are Despawned
Update examples to used gazebosim
Merge forward 6 to 7, 2022-10-21
Merge forward 6 to 7, 2022-10-06
Add information about
system paramter Adding tests for hydrodynamics
Fix Windows and Doxygen
Merge forward 3 to 6, 2022-08-16
Add support for specifying log record period
Common widget GzColor replacement
Replace plotIcon in ComponentInspector with GzPlotIcon
Component Inspector with common widget pose plotting
Change CODEOWNERS and maintainer to Michael
Replace pose in ViewAngle with GzPose
Gazebo Sim 7.0.0 (2022-09-27)
Fix some warnings in visualize_lidar.sdf
Lock step video recording is broken, disabling
Add code quotes to TestFixture.hh
Update URL in tutorial for
python_interfaces
Rename python library as gz.sim7
Fix documentation on visibility.sdf
Fix display of Pose3d and Vector3d
Use RTLD_NODELETE=true when loading libraries
Update headers for missing transitive includes
Add topic parameter to thrust plugin
Remove unused function
Fixed python build in gz-sim7
Fix Windows and Doxygen
Fix gz_TEST paths
Fix two tests
Add Metal support to Gazebo for macOS
Add information about
system paramter Adding tests for hydrodynamics
Fix Windows and Doxygen
Introduces new mesh formats to the drag&drop err
Add support for specifying log record period
Common widget GzColor replacement
Add option to disable building python bindings
Replace plotIcon in ComponentInspector with GzPlotIcon
Component Inspector with common widget pose plotting
🕐 Tock: Remove Fortress deprecations
Change CODEOWNERS and maintainer to Michael
Replace pose in ViewAngle with GzPose
Update gz-sensors branch in example
Deprecations, ign -> gz
Migrate config and log directories
ign to gz
Just the ABI breaking parts of #1560
Supply spherical coords when loading DEMs
Bump actions dependencies to Ogre 2.3
Install gz packages instead of ignition
Use stepping field in message
Don’t use ‘EachNew’ in ForceTorque PreUpdate function
Test case for simulation reset with detachable joints
Fix Python bindings
ign -> gz Provisional Finale: Source Migration : gz-sim
ign -> gz CMake, Python, Partial Source, and File Migrations : gz-sim
Tutorial for mesh distortion in Blender Python
Use new has connections function
Fix compilation of scene broadcaster test
Restore CXX_STANDARD 17
ign -> gz Shared Lib Migration : gz-sim
Garden: fix windows CI build
Implement system Reset interface for Sensors and SceneBroadcaster
ign -> gz Partial Docs Migration and Project Name Followups : gz-sim
Update GoogleTest to latest version
Rename CMake project to gz
Detect gz program instead of using CMake module to check for gz-tools
ign -> gz CLI Migration : gz-sim
Use new Joint APIs for Parent/Child name
Expose rendering teardown event
Add QML Debugging support
[ign -> gz] CMake functions
ign -> gz Macro Migration : gz-sim
Allow rendering to be forced externally
Apply shininess value to visuals
ign -> gz Environment Variable Migration
More missing math includes and math::clock fixes
Rename ignition to gz in #1519.
Use pose multiplication instead of subtraction
Add missing gz-math includes
[ign ➡️ gz] Logo, docs, tools
Remove ign-rendering SetTime hack
ign -> gz: namespaces, .gz directory
Update documentation in the linear battery plugin example.
Use gz/sim/test_config
Quality of life improvements for examples_build test
Update test log for gz components
Migrate CMake files
Migrate sources in src, test, examples, and include
Create redirection aliases
Move header files with git mv
Implement reset interface in the physics system
Use uint64_t with gazebo-entity user dataa
Depend on math7 and remove Bionic packages
Used Light ign-msgs is_light_off
Use message field visualize_visual
Tweaks to python docs
Use utils instead of ign-cmake utilities
Remove internal python bindings for sdformat
Bumps in garden : ign-utils2, ign-plugin2
Fix deprecation warnings for ModelPhotoShoot
Remove unused View::Clone method
replace deprecated common::SubMesh::MaterialIndex() with GetMaterialIndex()
Make WindEffects configurable on a location basis
Fix faulty assumption in INTEGRATION_log_system
Clean up various warnings caught by clang12
Fix visibility and add documentation
Preserve sign of thrust_coefficient
Support world reset
Added DEM support
Remove Bionic from future releases (Garden+)
Add support for wide angle camera in sensors system
Enable WorldPose component on TrajectoryFollower
Eliminates std::filesystem usage in utils.cc
Emitter migration
[Garden] Make tests run as fast as possible
Mark Component::Clone as const
Improve Sensor::Update call
Thruster plugin: accept angular velocity and provide feedback on topic
Re-enable triggered publisher tests
Bumps in garden: use ign-math7 and dependents
Update Docker instructions for Garden
Bumps in garden :
ci_matching_branch/bump_garden_ign-gazebo7
Bumps in garden : ign-gazebo7
Clarify available Ignition Versions
Add error message for non-zip files in playback mode
Bump main to 7.0.0~pre1
update CODEOWNERS
Gazebo Sim 6.x
Gazebo Sim 6.16.0 (2024-01-12)
Allow using plugin file names and environment variables compatible with Garden and later
Update friction parameters for skid steer example
Relax pose check in actor no mesh test
Fix macOS test failures by registering components in the core library
Fix for sensor pointer null when navsat plugin in included in sdf
Fix another deadlock in sensors system
Backport component inspector Vector3d width fix
Bump Fuel model version in test
Infrastructure
Gazebo Sim 6.15.0 (2023-08-16)
Fix Joint Position Controller Behaviour Described in #1997
Fix a minor issue in the documentation of the server API
Use sdf::Element::FindElement instead of GetElement in ApplyLinkWrench
Backport sensors system threading optimization changes
Adds a warning if the
Server
method of aTestFixture
is called beforeFinalize
Protobuf: Do not require version 3 do support Protobuf 4.23.2 (23.2)
Disable pybind11 on Windows by default
Print an error message when trying to load SDF files that don’t contain a
<world>
Port record topic fix
Allow re-attaching detached joint
Enable GzWeb visualization of markers by republishing service requests on a topic
Small fixes to gz headers
Speed up Resource Spawner load time by fetching model list asynchronously
Use ignition::gazebo:: in class instantiation
Add missing cmake exports from core library
Add tutorial on migrating the Sensor class from gazebo classic
Add tutorial on migrating the Actor class from gazebo classic
Fix use of actors that only has trajectory animation
Add tutorial on migrating the Joint class from gazebo classic
Add tutorial on migrating the Light class from gazebo classic
Infrastructure
Rename COPYING to LICENSE
Add Light class
Resolve inconsistent visibility on ign-gazebo6
Relax msg count check in RF comms integration test
Add Actor class
Add Sensor class
Allow to change camera user hfov in camera_view plugin
Add Joint class
Add SensorTopic component to rendering sensors
Use a queue to track component registration from mulitiple sources
Document behaviour changes introduced #1784
Partial backport of 1728
Fix triggered camera test by waiting for rendering / scene to be ready
Backport portion of #1771 to fix command-line test
cmdsim.rb: fix ruby syntax
Fix some windows warnings (C4244 and C4305)
Minor optimization to transform control tool
Inherit material cast shadows property
Fix record topic
Remove duplicate Fuel server used by ResourceSpawner
Re-add namespace
Fix QML warnings regarding binding loops
Update documentation on
UpdateInfo::realTime
Add jennuine as GUI codeowner
remove PlotIcon
ign -> gz
Added collection name to About Dialog
Citadel: Removed warnings
Remove actors from screen when they are supposed to
Readd namespaces for Q_ARGS
Remove redundant namespace references
Gazebo Sim 6.14.0 (2022-12-29)
Fix Ackermann plugin zero linVel turningRadius bug
Header guard fix for battery power load component
Add interface to allow systems to declare parameters
Adding battery consumers and extra fixes
Disable tests that require dartsim on windows
Added move camera to model service
Add spin box to View Angle plugin for configuring view control sensitivity
Sync View Angle GUI with view controller
Hydrodynamics flags test strengthening
Fixed Fortress tests related to lights
Allow to move to model from Angle view plugin
Fixed light entity number
Check AddBvnAnimation return value
Add checkbox in view angle plugin for toggling view control reference visual
Adds support for hydrodynamic cross terms
Addresses flakiness in
Hydrodynamics.VelocityTestInOil
.Fix minor bugs in RFComms plugin
Gazebo Sim 6.13.0 (2022-11-04)
Fix two tests on Windows
3 to 6 20221013
Some minor changes to hydrodynamic flags test
Fix thruster integration test
Fix scene_broadcaster_system test
Script and tutorial for generating procedural datasets with Blender
Enable use of ign gazebo -s on Windows (take two)
Removed unused speedlimit file
Fortress: Removed warnings
Enable/Disable individual hydrodynamic components.
Adding thrust coefficient calculation
Restore Add System GUI plugin
Return absolute path when finding a resource
Adds sky cubemap URI to the sky.proto’s header
Update triggered_publisher.sdf
Add ResourceSpawner example file
Enable inherited model topic name.
Fix loading render engine plugins in GUI
Add a service to trigger functionality
Fix installation instructions on Ubuntu 22.04
Fix reference link in ackermann steering
Gazebo Sim 6.12.0 (2022-08-30)
Add topic parameter to thrust plugin
Add information about
<topic>
system parameterAdding tests for hydrodynamics
Fix Windows and Doxygen
Gazebo Sim 6.11.0 (2022-08-17)
Add support for specifying log record period
Common widget GzColor replacement
Replace plotIcon in ComponentInspector with GzPlotIcon
Component Inspector with common widget pose plotting
Change CODEOWNERS and maintainer to Michael
Replace pose in ViewAngle with GzPose
Add system to an entity through Component Inspector
Quick start dialog
Quiet libSDFormat console on –verbose 0
New Apply Link Wrench system
Add Tf publishing to AckermannSteering system
Fix component updates
Implement vector3 with common widget vector3
Fix to modelphotoshoot test
Update log playback gui config
Helper function to get an entity from an entity message
Fix compilation of scene broadcaster test
Ignition -> Gazebo
Add Model::CanonicalLink getter
Implement Pose3d with common widget pose
Fix UNIT_Server_TEST on Windows
Use pytest to generate junit xml files for python tests
Refactor: Utilizes function to load animations
Utilizes function to sequence trajectories
Disable MacOS flakies Citadel
Gazebo Sim 6.10.0 (2022-06-24)
Expose the ability to stop a server from C++
Fix various Protobuf Windows warnings
New service for adding systems to an entity
Added particle emitters to scene broadcaster
Use more
sdf::Plugin
instead ofsdf::ElementPtr
Depend on common 4.5.1
Update README links
Add bounding boxes into the label system plugin
Odometry publisher: also publish
Pose_V
(TF)Fix clang warning from Thruster plugin
Fix locks in Visualize Lidar GUI plugin
Bash completion for flags
Fix sensors battery state test
Add new
GZ_GUI_RESOURCE_PATH
to help messageFix regression with camera sensors not using the background color set in
<scene>
Check RGBD camera sensor connection
Optimize sensor updates
System inspector GUI widget
Scene update resource finder
Updating hydrodynamics plugin description
Makes thruster stop when battery runs out.
Fix Documentation Header.
Adding rssi
Delete unused gazebo.hh.in
- books:
Fixed broken URL link to gazebo documentation
View polyline collisions on the GUI
Extruded 2D polyline geometries
Fix fuel url
Camera trigger integration test
Extend Multicoptor Control system to include nested model inertial params
Remove dead ign.cc file
Test case to check if velocity limits are applied to joints
SceneBroadcaster: Use double for state publish frequency instead of int
Revert format change
Fix finding DART on macOS
Skip serializing nested model with
//pose/@relative_to
attributeFix running simulation with no world specified on the command line
Add repo specific issue templates
python: release GIL when running server
python: remove semicolons
Bump rendering dependency version
Improve contact sensor / visualization performance
Set simulation time to Rendering
Gazebo Sim 6.9.0 (2022-04-14)
Add new
RFComms
systemAdd comms infrastructure
Fix CMake version examples and bump plugin version
Make sure pose publisher creates valid pose topics
Add Ubuntu Jammy CI
Removed
screenToPlane
method and userendering::screenToPlane
Supply world frame orientation and heading to IMU sensor (#1427)
Add desktop entry and SVG logo
Fix segfault at exit
Add Gaussian noise to Odometry Publisher
Gazebo Sim 6.8.0 (2022-04-04)
ServerConfig accepts an sdf::Root DOM object
Disable sensors in sensors system when battery is drained
Referring to Fuel assets within a heightmap
Add the Model Photo Shoot system, port of Modelpropshop plugin from Gazebo classic
Distortion camera integration test
Add wheel slip user command
SceneBroadcaster: only send changed state information for change events
Fortress: Install Ogre 2.2, simplify docker
Disable tests that are expected to fail on Windows
Added user command to set multiple entities
Fix JointStatePublisher topic name for nested models
add initial_position param to joint controller system
Component inspector: refactor Pose3d C++ code into a separate class
Prevent hanging when world has only non-world plugins
Toggle Light visuals
Disable PeerTracker.PeerTrackerStale on macOS
Disable ModelCommandAPI_TEST.RgbdCameraSensor on macOS
Don’t mark entities with a ComponentState::NoChange component as modified
Add gazebo Entity id to rendering sensor’s user data
Allow to turn on/off lights
Added headless rendering tutorial
Add xyz and rpy offset to published odometry pose
Fix visualization python tutorial
Populate GUI plugins that are empty
Gazebo Sim 6.7.0 (2022-02-24)
Added Python interfaces to some Gazebo Sim methods
Use pose multiplication instead of addition
Disables Failing Buoyancy Tests on Win32
Extend ShaderParam system to support loading different shader languages
Populate names of colliding entities in contact points message
Refactor System functionality into SystemManager
GzSceneManager: Prevent crash boom when inserted from menu
Gazebo Sim 6.6.0 (2022-02-24)
Fix accessing empty JointPosition component in lift drag plugin
Add parameter to TrajectoryFollower stop rotation when bearing is reached
Support disabling pose publisher from publishing top level model pose
Added more sensor properties to scene/info topic
Adding ability to pause/resume the trajectory follower behavior.
Logs a warning if a mode is not clearly sepecified.
JointStatePublisher publish parent, child and axis data
Fixed light gui component inspector
Fix UNIT_SdfGenerator_TEST
Add elevator system
Removed unused variables in shapes plugin
Gazebo Sim 6.5.0 (2022-02-15)
New trajectory follower system
Extend ShaderParam system to support textures
Adds a
Link::SetLinearVelocity()
methodFix weird indentation in
Link.hh
Limit thruster system’s input thrust cmd
Load and run visual plugin (system) on GUI side
Log an error if JointPositionController cannot find the joint. (citadel retarget)
Update source install instructions
Document the
<topic>
option for JointPositionController.Fix typo in EntityComponentManager
Buoyancy: fix center of volume’s reference frame
Fix graded buoyancy problems
Add surface to buoyancy engine. (retarget fortress)
Remove EachNew calls from sensor PreUpdates
Prevent GzScene3D 💥 if another scene is already loaded
Fix various typos on API documentation
Optional orientation when spawning entity using spherical coordinates
Cleanup update call for non-rendering sensors
Documentation Error
Min and max parameters for velocity, acceleration, and jerk apply to linear and angular separately.
Add project() call to examples
Implement /server_control::stop
Gazebo Sim 6.4.0 (2021-01-13)
Disable more tests on Windows
Adding angular acceleration to the Link class
Add world force
Add NavSat sensor (GPS)
Light Commands via topic
Support battery draining start via topics
Add visibility to ModelEditorAddEntity to fix Windows
Make tests run as fast as possible
Fix visualize lidar
Disable user commands light test on macOS
Skip failing Windows tests
Gazebo Sim 6.3.0 (2021-12-10)
View entity frames from the GUI
Model editor
Send state message when components are removed
Docker fixes for Fortress
Added sensor plugin to be able to visualize camera in
plane_propeller_demo.sdf
Update SdfGenerator to save link and sensor data to file
Fix buoyancy not being applied for one iteration
Increase maximum values in ViewAngle widget and increase its size
Fix the force-torque sensor update rate
Gazebo Sim 6.2.0 (2021-11-16)
Configurable joint state publisher’s topic
Thruster plugin: add tests and velocity control
Prevent creation of spurious
<plugin>
elements when saving worldsAdd
sdfString
toServerConfig
’s copy constructor.Added support for tracked vehicles
Add components to dynamically set joint limits
Remove bounding box when entities are removed
Fix updating component from state
Extend odom publisher to allow 3D
Support copy/paste
Tweaks install instructions
Publish 10 world stats msgs/sec instead of 5
Add functionality to add entities via the entity tree
Get updated GUI ECM info when a user presses ‘play’
Create expanding type header to reduce code duplication
minimal_scene.sdf
example: addcamera_clip
paramsSensor systems work if loaded after sensors
Support printing sensors using
gz model
Set camera clipping plane distances from the GUI
Fix generation of systems library symlinks in build directory
Add a default value for
isHeadlessRendering
.Component inspector
Edit material colors
Fix integers and floats
Prevent a segfault when updating
Use
uint64_t
for Entity IDs
Support setting the background color for sensors
Select top level entity not visual
Update create entity offset on GUI side
Update Select Entities GUI plugin to use Entity type
Notify other GUI plugins of added/removed entities via GUI events
Gazebo Sim 6.1.0 (2021-10-25)
Updates to camera video record from subt
Use the actor tension parameter
Better protect this->dataPtr->initialized with renderMutex.
Use QTimer to update plugins in the Qt thread
Adjust pose decimals based on element width
JointPositionController: Improve misleading error message
Fixed IMU system plugin
Prevent crash and print error
Create GUI config folder before copying config
Add support for configuring point size in Visualize Lidar GUI plugin
Set a cloned joint’s parent/child link names to the cloned parent/child link names
Performance: use std::unordered_map where possible in SceneManager
Fix transform controls
Fix View Angle’s home button
Fix light control standalone example
Parse new param for enabling / disabling IMU orientation output
Gazebo Sim 6.0.0 (2021-10-01)
Deprecated GzScene3D in favor of MinimalScene
Fix GuiRunner initial state and entity spawn timing issue
Buoyancy plugin upgrade
Fix non desired window opening alongside Gazebo GUI
Documentation
Update to latest SDFormat changes
Suppress missing canonical link error messages for static models
Heightmap fixes
Place config files in a versioned directory
Fix GUI crash when accessing bad rendering UserData
Fix performance issue with contact data and AABB updates
Enable new policy to fix protobuf compilation errors
Support locked entities, and headless video recording using sim time
Label Component & System, segmentation camera support
Joint Force-Torque Systems Plugin
Add support for cloning entities
🌐 Spherical coordinates
Populate JointConstraintWrench from physics
Buoyancy engine
Infrastructure
Update on resize instead of pre-render / render
Add a flag to force headless rendering mode
Remove unused Gazebo GUI header
Adds velocity control to JointPositionController.
Collada world exporter now exporting lights
Workaround for setting visual cast shadows without material
Fix selection buffer crash on resize
Remove extra xml version line in pendulum_links example world
Enable sensor metrics on example worlds
Add ESC to unselect entities in select entities plugin
Visualize joints
Deprecate particle emitter, and use scatter ratio in new particle mes…
Removed unused variable in Shapes plugin
Use root.Model()
Add ModelSDF serializer
Entity tree: prevent creation of repeated entity items
Use statically-typed views for better performance
Upgrade gz-sensors and support custom sensors
Fix entity creation console msg
Fix crash in the follow_actor example
Removed pose topic from log system
Be more specific when looking for physics plugins
Complaint if Joint doesn’t exists before adding joint controller
[DiffDrive] add enable/disable
Fix component inspector shutdown crash
Setting the intiial velocity for a model or joint
Examples and tutorial on using rendering API from plugins
Add missing GZ_SIM_VISIBLE macros
Fix visibility macro names when used by a different component (Windows)
No install apt recommends and clear cache
Support adding systems that don’t come from a plugin
Fix tests that use multiple root level models or lights
Make Gazebo Sim aware of SetCameraPassCountPerGpuFlush
Visualize center of mass
Transparent mode
Visualize inertia
Remove deprecations: tock 🕑
Removed and moved tape measure and grid config to gz-gui
Update wireframe visualization to support nested models
Multi-LRAUV Swimming Race Example
Add view control gui plugin and support orthographic view
Wireframe mode
Explain why detail::View symbols are visible
Bump dependencies in fortress
Gazebo Sim 5.x
Gazebo Sim 5.4.0 (2022-03-31)
Add the Model Photo Shoot system, port of Modelpropshop plugin from Gazebo classic
Add wheel slip user command
Added user command to set multiple entity poses
Component inspector: refactor Pose3d C++ code into a separate class
Toggle Light visuals
Allow to turn on/off lights
Added more sensor properties to scene/info topic
JointStatePublisher publish parent, child and axis data
Fixed light GUI component inspector
Fix
UNIT_SdfGenerator_TEST
Add elevator system
Removed unused variables in shapes plugin
Log an error if JointPositionController cannot find the joint. (citadel retarget)
Buoyancy: fix center of volume’s reference frame
Remove EachNew calls from sensor PreUpdates
Prevent GzScene3D 💥 if another scene is already loaded
Cleanup update call for non-rendering sensors
Documentation Error
Min and max parameters for velocity, acceleration, and jerk apply to linear and angular separately.
Add project() call to examples
Implement
/server_control::stop
👩🌾 Make depth camera tests more robust (#897)
Pull request #897) (#1257 (#1257)
Support battery draining start via topics
Make tests run as fast as possible
Fix visualize lidar
Skip failing Windows tests
Configurable joint state publisher’s topic
Thruster plugin: add tests and velocity control
Limit thruster system’s input thrust cmd
Gazebo Sim 5.3.0 (2021-11-12)
Prevent creation of spurious
elements when saving worlds Added support for tracked vehicles
Add components to dynamically set joint limits
Fix updating component from state
Extend odom publisher to allow 3D
Fix updating a component’s data via SerializedState msg
Sensor systems work if loaded after sensors
Fix generation of systems library symlinks in build directory
Edit material colors in component inspector
Support setting the background color for sensors
Use
uint64_t
for ComponentInspector Entity IDsFix integers and floats on component inspector
Gazebo Sim 5.2.0 (2021-10-22)
Fix performance level test flakiness
Updates to camera video record from subt
Better protect this->dataPtr->initialized with renderMutex.
Use QTimer to update plugins in the Qt thread
Adjust pose decimals based on element width
JointPositionController: Improve misleading error message
Fixed IMU system plugin
Cache top level and static to speed up physics system (Backport #656)
Prevent crash and print error
Performance: use std::unordered_map where possible in SceneManager
Fix light control standalone example
Parse new param for enabling / disabling IMU orientation output
Enable new policy to fix protobuf compilation errors
Fix performance issue with contact data and AABB updates
Support locked entities, and headless video recording using sim time
Update gz-sim4 changelog
bump version and update changelog
Remove unused Gazebo GUI header
Collada world exporter now exporting lights
Fixed GUI’s ComponentInspector light parameter
Workaround for setting visual cast shadows without material
Fix selection buffer crash on resize
Update DART deps to local
Remove extra xml version line in pendulum_links example world
Enable sensor metrics on example worlds
Make thermal sensor test more robust
Improved doxygen
Remove bitbucket-pipelines.yml
Removed unused variable in Shapes plugin
Entity tree: prevent creation of repeated entity items
Updates when forward-porting to v4
Don’t use $HOME on most tests (InternalFixture)
Fix entity creation console msg
Fix crash in the follow_actor example
Be more specific when looking for physics plugins
Drag and drop meshes into scene
Allow referencing links in nested models in LiftDrag
Complaint if Joint doesn’t exists before adding joint controller
Set protobuf_MODULE_COMPATIBLE before any find_package call
DiffDrive add enable/disable
Fix component inspector shutdown crash
Add UserCommands Plugin.
Expose a test fixture helper class
Fix logic to disable server default plugins loading
Porting Dome to Edifice: Windows, deprecations
removed unneeded plugin update
Functions to enable velocity and acceleration checks on Link
Support adding systems that don’t come from a plugin
3D plot GUI plugin
4 to 5
Fix joint controller without joint vel data
3 to 4
Model info CLI
gz model
Support Bullet on Edifice
Don’t create components for entities that don’t exist
Fix blender sdf export script and remove .material file from collada light export test
Heightmap physics (with DART)
Adds Mesh Tutorial
4 to 5
Fix updating GUI plugin on load
3 to 4
Physics system: update link poses if the canonical link pose has been updated
Add blender sdf export tutorial
Banana for Scale
Fix textures not exporting after loading a world that uses obj models
Fix documentation for the Sensor component
Make depth camera tests more robust
Use UINT64_MAX for kComponentTpyeIDInvalid instead of relying on underflow
Fix mouse view control target position
Gazebo Sim 5.1.0 (2021-06-29)
Depend on SDF 11.2.1, rendering 5.1 and GUI 5.1. Fix Windows.
Set gui camera pose
Refactor RenderUtil::Update with helper functions
Enables confirmation dialog when closing Gazebo.
Using math::SpeedLimiter on the diff_drive controller.
New example: get an ECM snapshot from an external program
Fix WindEffects Plugin bug, not configuring new links
Set collision detector and solver from SDF
Add Particle Emitter tutorial
Fix potentially flaky integration component test case
Added follow camera offset service
Remove unneeded camera follow offset checks
Using math::SpeedLimiter on the ackermann_steering controller.
Cleanup and alphabetize plugin headers
Fix race condition when rendering the UI
Removed duplicated code with rendering::sceneFromFirstRenderEngine
Remove unused headers in video_recoder plugin
Use moveToHelper from gz-rendering
Make halt motion act like a brake
Update collision visualization to support nested models
Adds support for ocean currents
Add conversion for particle scatter ratio field
Adding HaltMotion to physics plugin
ColladaExporter, export submesh selected
Remove tools/code_check and update codecov
Trigger delay
Map canonical links to their models
Fix included nested model expansion in SDF generation
Util: Use public API from libsdformat for detecting non-file source
Contacts visualization
Bump to gz-msgs 7.1 / sdformat 11.1, Windows fixes
Add functionalities for optical tactile plugin
Fix documentation for EntityComponentManager::EachNew
Bump gz-physics version to 3.2
Prevent crash on Plotting plugin with mutex
👩🌾 Fix Windows build and some warnings
Fix ColladaExporter submesh index bug
Fix macOS build: components::Name in benchmark
Feature/hydrodynamics
Don’t store duplicate ComponentTypeId in ECM
[TPE] Support setting individual link velocity
👩🌾 Enable Focal CI
Patch particle emitter2 service
Add odometry publisher system
[DiffDrive] add enable/disable
Update benchmark comparison instructions
Fix ‘invalid animation update data’ msg for actors
Fixed particle emitter forward playback
ECM’s ChangedState gets message with modified components
Fixed collision visual bounding boxes
Fix compute_rtfs arguments
Validate step size and RTF parameters
Fix component inspector shutdown crash
Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config
Do not pass -Wno-unused-parameter to MSVC compiler
Iterate through changed links only in UpdateSim
Update PlaybackScrubber description
Support configuring particle scatter ratio in particle emitter system
Fix diffuse and ambient values for ackermann example
Scenebroadcaster sensors
Add test for thermal object temperatures below 0 kelvin
[BULLET] Making GetContactsFromLastStepFeature optional in Collision Features
Make it so joint state publisher is quieter
Gazebo Sim 5.0.0 (2021-03-30)
Added Ellipsoid and Capsule geometries
Support individual canonical links for nested models
Mecanum wheels demo
Fixed collision visual bounding boxes
Fixed material colors for ackermann sdfs
Setting the intiial velocity for a model or joint
Remove static for maps from Factory.hh
Depend on cli component of ignition-utils1
Support SDFormat 1.8 Composition
Deprecate TmpIface: it’s leftover from prototyping
Bump in edifice: gz-common4
Plugin to spawn lights
Added light intensity
Examples and tutorial on using rendering API from plugins
Prepare GuiRunner to be made private
Deprecate some sim::gui events in favor of gz-gui events
Heightmap (rendering only)
Add image suffix to thermal camera topic name
Fix build with latest sdformat11 branch
Added run to time feature
Depend on ignition-utils1
Use double sided field in material msg
Add lightmap demo
Added renderOrder to convert functions
Compilation fixes for Windows
Documentation fixes
Replace deprecated function FreeGroup::CanonicalLink with FreeGroup::RootLink
Respect spotlight direction
Add UserCommands plugin to fuel.sdf
Change SelectedEntities to return a const ref
Use common::setenv for portability to Windows
Add missing GZ_SIM_VISIBLE macros
Fix deprecation warnings
Fix visibility macro names when used by a different component (Windows)
Bump edifice sdformat11 and gz-physics4
Use ComponentState::PeriodicChange in UpdateState to avoid forcing full scene update
Bump in edifice: gz-msgs7
Add support for sky
Infrastructure
Bump in edifice: gz-rendering5
Add 25percent darker view angle icons
Gazebo Sim 4.x
Gazebo Sim 4.14.0 (2021-12-20)
Support battery draining start via topics
Make tests run as fast as possible
Fix visualize lidar
Disable user commands light test on macOS
Gazebo Sim 4.13.0 (2021-11-15)
Prevent creation of spurious
<plugin>
elements when saving worldsAdd support for tracked vehicles
Add components to dynamically set joint limits
Fix updating component from state
Fix updating a component’s data via SerializedState msg
Sensor systems work if loaded after sensors
Fix generation of systems library symlinks in build directory
Edit material colors in component inspector
Support setting the background color for sensors
Use uint64_t for ComponentInspector Entity IDs
Fix integers and floats on component inspector
Gazebo Sim 4.12.0 (2021-10-22)
Fix performance issue with contact data and AABB updates.
Enable new CMake policy to fix protobuf compilation
Parse new param for enabling / disabling IMU orientation output.
Fix light control standalone example.
Performance: use std::unordered_map where possible in SceneManager.
Prevent crash when using
workflow PBR material. JointPositionController: Improve misleading error message.
Adjust pose decimals based on element width.
Better protect this->dataPtr->initialized with renderMutex.
Updates to camera video record from subt.
Fix performance level test flakiness.
Gazebo Sim 4.11.0 (2021-09-23)
Support locked entities, and headless video recording using sim time.
Gazebo Sim 4.10.0 (2021-09-15)
Fixed GUI’s ComponentInspector light parameter
Fix msg in entity_creation example
Fix selection buffer crash on resize
Fix crash in the follow_actor example
Fix joint controller with empty joint velocity data
Scale mode - Part2
Physics system: update link poses if the canonical link pose has been updated
Add Particle Emitter tutorial
Refactor RenderUtil::Update with helper functions
Remove unneeded camera follow offset checks
Added service to set camera’s follow offset
Using math::SpeedLimiter on the ackermann_steering controller.
All changes merged forward from gz-sim3
Gazebo Sim 4.9.1 (2021-05-24)
Make halt motion act like a brake.
Gazebo Sim 4.9.0 (2021-05-20)
Enable Focal CI.
[TPE] Support setting individual link velocity.
Don’t store duplicate ComponentTypeId in ECM.
Fix macOS build: components::Name in benchmark.
Fix documentation for EntityComponentManager::EachNew.
Add functionalities for optical tactile plugin.
Visualize ContactSensorData.
Backport PR #763.
Backport PR #536.
Add an optional delay to the TriggeredPublisher system.
Remove tools/code_check and update codecov.
add conversion for particle scatter ratio field.
Gazebo Sim 4.8.0 (2021-04-22)
Add odometry publisher system.
Patch particle emitter2 service.
Gazebo Sim 4.7.0 (2021-04-09)
Particle emitter based on SDF.
Fix log playback for particle emitters.
ECM’s ChangedState gets message with modified components.
Fixed collision visual bounding boxes.
Fix compute_rtfs arguments.
Validate step size and RTF parameters.
Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config.
Do not pass -Wno-unused-parameter to MSVC compiler.
Support configuring particle scatter ratio in particle emitter system.
Fix diffuse and ambient values for ackermann example.
Scenebroadcaster sensors.
Add thermal camera test for object temperature below 0.
[BULLET] Making GetContactsFromLastStepFeature optional in Collision Features
Fix joint controller GUI test.
Quiet warnings from Joint State Publisher.
Ackermann Steering Plugin.
Remove bounding box when model is deleted
Cache link poses to improve performance.
Check empty world name in Scene3d.
All changes up to 3.8.0.
Gazebo Sim 4.6.0 (2021-03-01)
Use a custom data structure to manage entity feature maps.
Limit scene broadcast publications when paused.
Report performer count in PerformerDetector plugin.
Cache top level and static to speed up physics system.
Support particle emitter modification using partial message.
Set LD_LIBRARY_PATH on Actions CI.
Fix flaky SceneBroadcaster test.
Add a convenience function for getting possibly non-existing components.
Add msg to show the computed temperature range computed from temperature gradient.
Add TF/Pose_V pub in DiffDrive.
Relax flaky performance test.
Improve velocity control test.
Validity check for user defined topics in JointPositionController.
Add laser_retro support.
Fix pose of plane visual with non-default normal vector.
Gazebo Sim 4.5.0 (2020-02-17)
Added particle system.
Add Light Usercommand and include Light parameters in the componentInspector
Added link to HW-accelerated video recording.
Fix EntityComponentManager race condition.
Add SDF topic validity check.
Add JointTrajectoryController system plugin.
Gazebo Sim 4.4.0 (2020-02-10)
Added issue and PR templates
Fix segfault in SetRemovedComponentsMsgs method
Make topics configurable for joint controllers
Add about dialog
Add thermal sensor system for configuring thermal camera properties
Gazebo Sim 4.3.0 (2020-02-02)
Non-blocking paths request.
Parallelize State call in ECM.
Allow to create light with the create service.
Added size to ground_plane in examples.
Fix finding PBR materials.
Publish all periodic change components in Scene Broadcaster.
Backport state update changes from pull request #486.
Fix code_check errors.
Visualize collisions.
Remove playback
SDF param in Dome. Tutorial on migrating SDF files from Gazebo classic.
World Exporter.
Model Creation tutorial using services.
Fix topLevelModel Method.
Add heat signature option to thermal system.
Add service and GUI to configure physics parameters (step size and RTF).
Refactor UNIT_Server_TEST.
Use Gazebo GUI render event.
Gazebo Sim 4.2.0 (2020-01-13)
Automatically load a subset of world plugins.
Fix to handle multiple logical cameras.
Improve gz tool support on macOS.
Add support for topic statistics on breadcrumb deployments.
Fix slot in Plotting plugin.
Fix shadow artifacts by disabling double sided rendering.
Kinetic energy monitor plugin.
Change nullptr to a int ptr for qt 5.15.2.
Generate valid topics everywhere (support names with spaces).
All changes up to version 3.7.0.
Gazebo Sim 4.1.0 (2020-12-11)
Update Dockerfiles to use focal images
Updated source build instructions for gz-sim4
Add tests for the AnimationTime component
Fix pose msg conversion when msg is missing orientation
Resolved updated codecheck issues
Use new backpack version in tests
Fix segfault in the Breadcrumb system when associated model is unloaded
Added user commands to example thermal camera world
Helper function to set component data
Remove unneeded if statement
Fix flaky RecordAndPlayback test in INTEGRATION_log_system
Make PeerTracker test more robust
Use a std::promise/std::future mechanism to avoid waiting in a looop until all
stepAck
messages are receivedOptical Tactile Sensor Plugin
All changes up to and including those in version 3.5.0 and version 2.25.0
Gazebo Sim 4.0.0 (2020-09-30)
Names with spaces: add string serializer
Filter mesh collision based on
collide_bitmask
propertyAdd force focus when mouse enters render window
Fixed docblock showGrid
More actor components and follow plugin
Filter the record menu and write the format to the file according to which button the user pushed (mp4 or ogv)
Fix scene manager losing header file
Fixed left menu events
Fix yaw units typo in Component Inspector plugin
Enable alpha based transparency on PBR materials by default
Qt auto scale factor for HiDPI displays
Sync components removal
Add error handling for JointAxis::SetXyz and remove use of use_parent_model_frame
Make some tests more robust
Fix Qt5 warnings for using anchors
Plotting Components Plugin
Visualize Lidar Plugin
Replaced common::Time for std::chrono
Tutorial, examples and documentation updates
Migration from BitBucket to GitHub
Use interpolate_x sdf parameter for actor animations
Actor skeleton animation (auto update mode)
Added support for removing sensors at runtime
Add support for visual visibility flags and camera visibility mask
Support
and Depend on gz-rendering4, gz-gui4, gz-sensors4
Axis-Aligned Bounding Boxes
Add window focus upon mouse entering the render window
Gazebo Sim 3.x
Gazebo Sim 3.15.1 (2024-01-05)
Update github action workflows
Fix macOS test failures by registering components in the core library
Bump Fuel model version in test
Fix a minor issue in the documentation of the server API
Use sdf::Element::FindElement instead of GetElement in ApplyLinkWrench
Adds a warning if the
Server
method of aTestFixture
is called beforeFinalize
Protobuf: Do not require version 3 do support Protobuf 4.23.2 (23.2)
Print an error message when trying to load SDF files that don’t contain a
<world>
Enable GzWeb visualization of markers by republishing service requests on a topic
Gazebo Sim 3.15.0 (2023-05-08)
Speed up Resource Spawner load time by fetching model list asynchronously
ign -> gz Migrate Ignition Headers : gz-sim
Infrastructure
Backport portion of #1771 to fix command-line test
cmdsim.rb: fix ruby syntax
Fix loading wold with record topic
Remove duplicate Fuel server used by ResourceSpawner
Re-add namespace for GUI render event
Fix QML warnings regarding binding loops
Update documentation on
UpdateInfo::realTime
Add jennuine as GUI codeowner
Remove plotIcon in Physics.qml for Component Inspector
Convert ignitionrobotics to gazebosim in tutorials
Added collection name to About Dialog
Remove compiler warnings
Update examples to use gazebosim.org
Remove actors from screen when they are supposed to
Readd namespaces for Q_ARGS
Gazebo Sim 3.X.X (20XX-XX-XX)
Gazebo Sim 3.13.0 (2022-06-01)
Extruded 2D polyline geometries
Add elevator system
Add desktop entry and svg logo
Delete unused
gazebo.hh.in
Add repo specific issue templates
Added user command to set multiple entities’ poses
Component inspector: refactor Pose3d C++ code into a separate class
Added more sensor properties to
scene/info
topicJointStatePublisher
publish parent, child and axis dataRemoved unused variables in shapes plugin
Log an error if
JointPositionController
cannot find the joint. (citadel retarget)Buoyancy
: fix center of volume’s reference frameRemove
EachNew
calls from sensor PreUpdatesPrevent
GzScene3D
💥 if another scene is already loadedAdd
project()
call to examplesImplement
/server_control::stop
👩🌾 Make depth camera tests more robust
Make tests run as fast as possible
Gazebo Sim 3.12.0 (2021-11-11)
Prevent creation of spurious
<plugin>
elements when saving worldsAdded support for tracked vehicles
Add components to dynamically set joint limits
Fix updating a component’s data via SerializedState msg
Sensor systems work if loaded after sensors
Fix generation of systems library symlinks in build directory
Backport sim::Util::validTopic() from ign-gazebo4.
Support setting the background color for sensors
Use uint64_t for ComponentInspector Entity IDs
Fix integers and floats on component inspector
Gazebo Sim 3.11.0 (2021-10-21)
Updates to camera video record from subt.
Fix performance level test flakiness.
Gazebo Sim 3.10.0 (2021-10-15)
Performance: use std::unordered_map where possible in SceneManager
Enable new CMake policy to fix protobuf compilation
Fix setting cast_shadows for visuals without material
Remove duplicate XML tag in pendulum_links example world
Enable sensor metrics on example worlds
Improved doxygen
JointPositionController: Improve misleading error message
Adjust pose decimals based on element width
Fixed IMU system plugin
Use QTimer to update plugins in the Qt thread
Gazebo Sim 3.9.0 (2021-08-16)
Entity tree: prevent creation of repeated entity items
Don’t use $HOME on most tests (InternalFixture)
Be more specific when looking for physics plugins
Drag and drop meshes into scene
Set protobuf_MODULE_COMPATIBLE before any find_package call
[DiffDrive] add enable/disable
Fix component inspector shutdown crash
Add UserCommands Plugin.
Setting the intiial velocity for a model or joint
Examples and tutorial on using rendering API from plugins
Add missing GZ_SIM_VISIBLE macros
Fix visibility macro names when used by a different component (Windows)
No install apt recommends and clear cache
Add 25percent darker view angle icons
Expose a test fixture helper class
Fix logic to disable server default plugins loading
removed unneeded plugin update
Functions to enable velocity and acceleration checks on Link
Support adding systems that don’t come from a plugin
3D plot GUI plugin
Add a convenience function for getting possibly non-existing components.
Fix topLevelModel method
World exporter
Fix finding PBR materials
Handle multiple logical cameras
Make some tests more robust
Fix codecheck
Hello world plugin added
Model info CLI
gz model
Don’t create components for entities that don’t exist
Adds Mesh Tutorial
Fix updating GUI plugin on load
Fix documentation for the Sensor component
Use UINT64_MAX for kComponentTpyeIDInvalid instead of relying on underflow
Fix mouse view control target position
Set GUI camera pose
Enables confirmation dialog when closing Gazebo.
Depend on gz-rendering 3.5
Using math::SpeedLimiter on the diff_drive controller.
New example: get an ECM snapshot from an external program
Fix WindEffects Plugin bug, not configuring new links
Fix potentially flaky integration component test case
Cleanup and alphabetize plugin headers
Removed duplicated code with rendering::sceneFromFirstRenderEngine
Remove unused headers in video_recoder plugin
Use moveToHelper from gz-rendering
Remove tools/code_check and update codecov
Add service and GUI to configure physics parameters
Fix documentation for EntityComponentManager::EachNew
Fix macOS build: components::Name in benchmark
Don’t store duplicate ComponentTypeId in ECM
[TPE] Support setting individual link velocity
👩🌾 Enable Focal CI
Update benchmark comparison instructions
Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config
Do not pass -Wno-unused-parameter to MSVC compiler
Scenebroadcaster sensors
Make it so joint state publisher is quieter
Gazebo Sim 3.8.0 (2021-03-17)
Add joint position controller GUI, also enable tests for GUI plugins
Remove visibility from headers that are not installed
Added screenshot to toolbar
Improve gz tool support on macOS
change nullptr to a int ptr for qt 5.15.2 bug
Kinetic energy monitor plugin
Use a std::promise/std::future to avoid busy waiting the step ack messages in NetworkManagerPrimary
clarified performer example
Add tutorial tweaks
Fix Qt5 warnings for using anchors
Update codeowners
Qt auto scale factor for HiDPI displays
Fix yaw units
Fixed docblock showGrid
Fix entity tree for large worlds
Master branch updates
Backport #561: Use common::setenv
Use a custom data structure to manage entity feature maps
Limit scene broadcast publications when paused
Fix flaky SceneBoradcaster test
Add TF/Pose_V publisher in DiffDrive
👩🌾 Relax performance test
👩🌾 Improve velocity control test
Add
laser_retro
supportFix pose of plane visual with non-default normal vector
Add About dialog
Make topics configurable for joint controllers
Also use Gazebo GUI render event
Tutorial on migrating SDF files from Gazebo classic
Visualize collisions
Backport state update changes from pull request #486
Publish all periodic change components in Scene Broadcaster
added size to
ground_plane
in examplesParallelize State call in ECM
Non-blocking paths request
Gazebo Sim 3.7.0 (2021-01-13)
Fix examples in migration plugins tutorial.
Added missing namespace in
detail/EntityComponentManager.hh
.Automatically load a subset of world plugins.
Update gtest to 1.10.0 for Windows compilation.
Updates to ardupilot migration tutorial.
Don’t make docs on macOS.
Gazebo Sim 3.6.0 (2020-12-30)
Fix pose msg conversion when msg is missing orientation
Address code checker warnings
Test fixes
Documentation updates
Fix segfault in the Breadcrumb system when associated model is unloaded
Added user commands to example thermal camera world
Helper function to set component data
Remove unneeded if statement in EntityComponentManager
Clarify how time is represented in each phase of a System step
Switch to async state service request
Update key event handling
Tape Measure Plugin
Move deselect and preview termination to render thread
Logical audio sensor plugin
add frame_id and child_frame_id attribute support for DiffDrive
Add ability to record video based on sim time
Add lockstep mode to video recording
Disable right click menu when using measuring tool
Gazebo Sim 3.5.0 (2020-11-03)
Updated source build instructions
More world APIs, helper function ComponentData
Improve fork experience
Fix a crash in the grid config plugin, set grid material
Document deprecation of log playback
<path>
SDF paramEnable mouse highlighting selection on resource spawner
Add support for custom render engines
Component Vector -> Map ECM Optimization
Gazebo Sim 3.4.0 (2020-10-14)
Fix gui sendEvent memory leaks
Support nested models
Generalize actor count and pose in actor population erb SDF
Add more link APIs, with tutorial
Add screenshots to GUI config tutorial
Fix adding performers to entity tree
Remove sidebar and put world control in bottom left for joint controller examples
Allow executing a blocking single Server run in both paused and unpaused states
Add camera video recorder system
Decrease time step for quadcopter world
Add support for moving the GUI camera to a pose
Remove
lib
+.so
from plugin’s nameEntityComponentManager::EachRemoved documentation fix.
Add more model APIs.
Update dimensions of the grid config.
Fix top-left toolbar layout so magnet shows.
Add instructions to bitmask world.
Add search and sort for resource spawner.
Fix source build instructions for gz-sim3.
Added playback scrubber GUI
Added wheel slip system plugin.
Enhanced log playback performance.
Tests & Warnings: Qt 5.14, breadcrumbs, Gui, gz_TEST
Added support for specifying topics to record.
Make sure OpenGL core profile context is used by GzScene3D.
Support relative paths for PBR materials
Add file extension automatically for record plugin.
Support spawning during log playback.
Add Render Engine Cmd Line option
Gazebo Sim 3.3.0 (2020-08-31)
Added marker array service.
Introduced a new parameter in the scene3D plugin to launch in fullscreen.
Fix issue #285 by adding checks for a marker’s parent.
Fix non-specified material error.
Added simulation world with large number of entities.
Fixed parsing of the touch plugin’ enabled flag.
Added buoyancy system plugin.
Implemented shift + drag = rotate in the GUI.
Backport collision bitmask changes
Added velocity command to TPE.
This version includes all features in Gazebo Sim 2.23.0
Gazebo Sim 3.2.0 (2020-05-20)
Merge gz-sim2 to gz-sim3
Gazebo Sim 3.1.0 (2020-05-19)
Port support for computing model bounding box in physics system
Add DetachableJoint: A system that initially attaches two models via a fixed joint and allows for the models to get detached during simulation via a topic.
Update physics state even when paused (not stepping)
Fix entity tree context menu position
Fix moving static model with link offset
Added Link::AddWorldWrench function that adds a wrench to a link.
Fix duplicate marker services and crash due to unset marker field
Support
s from Fuel Add support for thermal camera
Add window focus upon mouse entering the render window
Gazebo Sim 3.0.0 (2019-12-10)
Add example world for collide bitmask feature
Remove
sdf element from visuals that do not emit light in the example worlds Support for sdformat frame semantics
Support for relative path URIs for actors
Add rechargeable battery model
Add Marker Manager
Parse material emissive map, bump to msgs5 and transport8
Move function definitions to their correct locations in EntityComponentManager
Depend on gz-rendering3, gz-gui3, gz-sensors3
Rendering and Animating Actors
Gazebo Sim 2.x
Gazebo Sim 2.25.0 (2020-09-17)
Added wheel slip system plugin.
Enhanced log playback performance.
Tests & Warnings: Qt 5.14, breadcrumbs, Gui, gz_TEST
Added support for specifying topics to record.
Make sure OpenGL core profile context is used by GzScene3D.
Support relative paths for PBR materials
Add file extension automatically for record plugin.
Support spawning during log playback.
Gazebo Sim 2.24.0 (2020-09-03)
Resource env var, with transport interface.
Save http URIs (fix tests)
Insert Local Models.
Modernize actions CI.
Sensor topics available through components and GUI.
Customizable layouts - fully functional.
Add Fuel World Support.
Insert Fuel Models.
Disable rendering tests on macOS that are known to fail.
Fix tests on Blueprint.
Publish remaining breadcrumb deployments.
Gazebo Sim 2.23.0 (2020-07-28)
Deactivate PerformerDetector if its parent model gets removed.
Backport support for
s from Fuel #255
Gazebo Sim 2.22.0 (2020-07-22)
Allow zero or more key/value pairs to be added to detection header information.
Gazebo Sim 2.21.0 (2020-07-16)
Added support for controlling which joints are published by the JointStatePublisher.
Added an additional pose offset for the performer detector plugin.
Fixed battery issues and updated tutorial.
Gazebo Sim 2.20.1 (2020-06-18)
Properly add new models into the scenegraph. With this fix, when a model is spawned it will be added into the graph and resulting calls to the
scene/info
service will return a correctmsgs::Scene
.
Gazebo Sim 2.20.0 (2020-06-09)
Updated battery model to stop battery drain when there is no joint velocity/force command, and added a recharging trigger.
Fix segfault in the Breadcrumbs system
Added an
<odom_topic>
element to the DiffDrive system so that a custom odometry topic can be used.
Gazebo Sim 2.19.0 (2020-06-02)
Use updated model names for spawned models when generating SDFormat
Allow joint force commands (JointForceCmd) to dscharge a battery.
Allow renaming breadcrumb models if there is a name conflict
Add TriggeredPublisher system
Add PerformerDetector, a system for detecting when performers enter a specified region
Gazebo Sim 2.18.0 (2020-05-20)
Added a
/world/<world_name>/create_multiple
service that parallels the current/world/<world_name>/create
service. Thecreate_multiple
service can handle angz::msgs::EntityFactory_V
message that may contain one or more entities to spawn.DetachableJoint system: Add option to suppress warning about missing child model
Gazebo Sim 2.17.0 (2020-05-13)
Allow battery plugin to work with joint force systems.
Make breadcrumb static after specified time
Disable breadcrumbs if the
max_deployments
== 0.Add static pose publisher and support pose_v msg type in pose publisher system
Refactor Gui.hh so that the Gazebo GUI can be ran from other packages
Add ability to save worlds to SDFormat
Add window focus upon mouse entering the render window
Gazebo Sim 2.16.0 (2020-03-24)
Add support for computing model bounding box in physics system
Add DetachableJoint: A system that initially attaches two models via a fixed joint and allows for the models to get detached during simulation via a topic.
Update physics state even when paused (not stepping)
Fix entity tree context menu position
Fix moving static model with link offset
Add support for setting visual transparency through SDF
Add
JointPositionReset
andJointVelocityReset
components to reset the joint state.Logging meshes and materials
List plugin env vars
Fix protobuf / clang warnings
Component inspector
Log compress
Set process titles
Add custom user snapping
Add GUI to configure grid
Add multiple entity selection to view angle
Highlight selected entities
Log record overwrite
Add copyright to QML files
Fix shift translation bug
Gazebo Sim 2.15.0 (2020-02-07)
Fix seeking back in time in log playback
Fix the deprecated gz-sim command line
Always use the latest render texture in scene3d
Remove redundent messages when levels get unloaded
View angle plugin
Support breadcrumb performers
Drag and drop Fuel object into mouse position
Add hotkey keybindings
Gazebo Sim 2.14.0 (2020-01-10)
Use Actuator component to communicate between MulticopterVelocityControl and MulticopterMotorModel systems
Backport fix to insert multiple lights with same name
Get all component types attached to an entity
Fix tooltips on entity tree
Gazebo Sim 2.13.0 (2019-12-17)
Add Multicopter velocity controller
Fix crash when removing an entity being followed
Add option to right click and remove nodes
Fix jumpy log playback
Remove Scene3d Text anchors
Show grid using SDF file
Gazebo Sim 2.12.0 (2019-11-25)
Parse visual cast shadows and add CastShadows component
Update SceneBroadcaster to publish state msg for world with only static models
Add log video recorder
Rechargeable battery model
Add Breadcrumbs system
Drag models from Fuel
Improvements to GUI configuration
Prevent crash when attempting to load more than one render engine per process
Gazebo Sim 2.11.0 (2019-10-23)
Handle Relative URIs
Avoid using invalid/unsupported joints
Add mutex to protect views from potential concurrent access
Add
Link::WorldKineticEnergy
for computing total kinetic energy of a link with respect to the world frame.Improve steering behavior of example tracked vehicle
Rewind / reset and seek
Add Follow mode to GUI
Gazebo Sim 2.10.0 (2019-09-08)
Custom odom frequency in sim time
Add Move To gui plugin
Gazebo Sim 2.9.0
Use the JointSetVelocityCommand feature to set joint velocities
Gazebo Sim 2.8.0 (2019-08-23)
Add video recorder gui plugin
Vertical rays for lidar demo
Print world path when using cli
Gazebo Sim 2.7.1
Fix order of adding and removing rendering entities, and clean up mesh materials in the SceneManager.
Gazebo Sim 2.7.0
Move creation of default log path to ServerConfig. This lets both console logs and state logs to be stored in the same directory. The console messages are always logged. Allow state log files to be overwritten.
Baseline for stereo cameras
Fix log playback with levels. This drops support for logs created before v2.0.0.
Add worker threads for System PostUpdate phase
Added a test runner for executing an SDF and recording simulation rates. See the
test/performance/READEM.md
file for more info.
Gazebo Sim 2.6.1 (2019-07-26)
Clear stepMsg before populating it
Gazebo Sim 2.6.0 (2019-07-24)
Improve performance of Pose Publisher
Fix distributed sim
Gazebo Sim 2.5.0 (2019-07-19)
The LinearBatteryPlugin system publishes battery state
Gazebo Sim 2.4.0 (2019-07-17)
Bundle scene updates in sensor system
Gazebo Sim 2.3.0 (2019-07-13)
Improve physics system peformance by skipping static model updates. Components state information has been incorporated, which is used to indicate if a component change is periodic (such as through a physics update) or a one-time change (such as through a user command).
Add sdf parameter to battery to start draining only when robot has started moving
Improve SceneBroadcaster peformance by 1) Limit message generation if subscribers to pose topics are not present, 2) Set world stats message instead of copying the message, 3) Suppress scenegraph updates when there are no new entities, 4) Make better use of const functions, 5) Prevent creation of msgs::SerializedStep every PostUpdate, 6) Only serialized and transmit components that have changed.
Gazebo Sim 2.2.0
The DiffDrive system publishes odometry information.
Allow attaching plugins to sensors from a server config.
Remove world name from frame_ids
Fix deadlock when spawning robots
Set default topics for rendering sensors
Support custom random seed from the command line.
Gazebo Sim 2.1.0
RenderUtil fix bad merge: check for existing entities in GzScene3D on initialization.
Allow sensors to load plugins.
Parse and load submesh geometry in visuals.
Allow setting the update frequency of pose publisher.
Added RGBD camera sensor.
Fix Docker scripts.
Support log playback from a different path
Gazebo Sim 2.0.0
RenderUtil: check for existing entities in GzScene3D on initialization.
SceneBroadcaster: only send pose state periodically.
PeerTracker: increase distributed simulation peer tracking timeout.
MultiCopterMotorModel: add mutex to protect motor velocity command.
Tweaks to example worlds
DiffDrive system: add topic as system parameter.
Log entity creation and deletion
Multicopter motor model
Fix removing selected entity
Collision serialization
Add support for moving and rotating models
Pose commands
Level performers can be added at runtime using a service call. See the levels tutorial for more information.
Update worlds to GzScene3D
Reduce logging file size
Update PosePublisher system to publish sensor poses and to use scoped names for frame ids
Fix gui plugin linking issue
Toolbar colors
Rename Scene3D gui plugin to GzScene3D
Fix distributed sim documentation
Port Scene3D gui plugin from gz-gui. Renamed to GzScene3D.
Entity tree UI
Add rendering component
Update Camera and DepthCamera components to use sdf::Sensor object instead of an sdf::ElementPtr.
Added system for gz::sensors::AirPressureSensor.
Support conversion and serialization of Imu components. IMU sensors are loaded from an SDF DOM object.
Throttle sensors update rate
Fix changing themes
Battery tweaks
Support conversion and serialization of PBR parameters in a material component
Joint state pub
Update Altimeter component to use sdf::Sensor object instead of an sdf::ElementPtr.
Update docker nightly dependencies
Gz tool
State broadcast
Use world statistics message on network
Update Magnetometer component to use sdf::Sensor object instead of an sdf::ElementPtr.
Fix Scene3D loading empty world
Support conversion and serialization of scene and light components
Operators instead of De/Serialize
Remove PIMPL from Component
Delay scene broadcaster transport setup
Report link poses from secondaries during distributed simulation, using a cache
Restore log playback
ECM changed state
Joint serialization
Use scene ambient and background color information in sensor configuration.
Performance benchmarking
Remove emissive component from visual materials
Serialization for more components
Added an SDF message to the start of log files.
Unify network and sync managers
Add PerformerLevels component
Distributed sim deprecate envs
Use gz-sensors magnetometer sensor plugin
Use gz-sensors altimeter sensor plugin
Use gz-sensors imu sensor plugin
Depend on gz-sensors rendering component
Gazebo Sim 1.x
Gazebo Sim 1.X.X
Add Wind Plugin (Ported from Gazebo classic)
Port battery plugin from Gazebo classic
Use ISO timestamp for default log path
Logging tutorial
Joystick SDF small typos
Add
Link
: a convenience class for interfacing with link entitiesAdded LiftDragPlugin (ported from Gazebo classic)
Logging refactor unique path functions to gz-common
Added test for log record and playback.
Add ApplyJointForce system
More gz-msgs <-> SDF conversions: Inertial, Geometry, Material
Logging command line support
Remove inactive performers instead of setting static
Use state instead of pose in distributed simulation
Distributed implies levels
Add a basic JointController system
Enforce component type uniqueness
Clean CI: disable test known to fail on OSX
Logical camera topic name check
Added command line options to configure distributed simulation. These will replace the environment variables.
Add systems to queue before actually adding them to runner
Added a docker image that uses the Gazebo meta package
Move some design docs to tutorials
Disable GUI when using distributed simulation
Bring component type names back
A few tweaks to logging
Handle friction coefficients
Change private msgs namespace
Set tutorial titles
Example tunnel world
Conversion from chrono to gz-msgs
Prevent error message when using levels
Gazebo Sim 1.1.0 (2019-03-15)
Distributed performers running in lockstep
Fix documentation tagfiles
Convert gui library into a component
include
wherever special int types like uint64_t are used Move network internal
Logging / playback
ECM state streaming
Unversioned system libraries
Gazebo Sim 1.0.2 (2019-03-12)
Use TARGET_SO_NAME to fix finding dartsim plugin
Gazebo Sim 1.0.1 (2019-03-01)
Update gazebo version number in sdf files
Gazebo Sim 1.0.0 (2019-03-01)
Initial release
Gazebo Sim 0.x
Gazebo Sim 0.1.0
Add support for joints
Use SimpleWrapper for more component types
Create EventManager and delegate System instantiation to SimulationRunner
Integrate gz-gui
Remove some build dependencies.
Added basic Entity class.
Added a basic System class.