Skip to content

Commit

Permalink
Merge branch 'gz-sim8' into patch-19
Browse files Browse the repository at this point in the history
  • Loading branch information
mergify[bot] authored Jun 26, 2024
2 parents d7488a7 + cd9a855 commit 7b995af
Show file tree
Hide file tree
Showing 65 changed files with 1,963 additions and 215 deletions.
11 changes: 11 additions & 0 deletions .github/workflows/package_xml.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
name: Validate package.xml

on:
pull_request:

jobs:
package-xml:
runs-on: ubuntu-latest
name: Validate package.xml
steps:
- uses: gazebo-tooling/action-gz-ci/validate_package_xml@jammy
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
#============================================================================
# Initialize the project
#============================================================================
project(gz-sim8 VERSION 8.3.0)
project(gz-sim8 VERSION 8.4.0)
set (GZ_DISTRIBUTION "Harmonic")

#============================================================================
Expand Down Expand Up @@ -66,7 +66,7 @@ cmake_dependent_option(USE_DIST_PACKAGES_FOR_PYTHON
#============================================================================

# Setting this policy enables using the protobuf_MODULE_COMPATIBLE
# set command in CMake versions older than 13.13
# set command when cmake_minimum_required is less than 3.13
set(CMAKE_POLICY_DEFAULT_CMP0077 NEW)
# This option is needed to use the PROTOBUF_GENERATE_CPP
# in case protobuf is found with the CMake config files
Expand Down Expand Up @@ -136,7 +136,7 @@ set(GZ_PHYSICS_VER ${gz-physics7_VERSION_MAJOR})

#--------------------------------------
# Find gz-sensors
gz_find_package(gz-sensors8 REQUIRED
gz_find_package(gz-sensors8 REQUIRED VERSION 8.2.0
# component order is important
COMPONENTS
# non-rendering
Expand Down
77 changes: 77 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,82 @@
## Gazebo Sim 8.x

### Gazebo Sim 8.4.0 (2024-06-12)

1. Add pause run tutorial
* [Pull request #2383](https://github.com/gazebosim/gz-sim/pull/2383)

1. Fix warning message to show precise jump back in time duration
* [Pull request #2435](https://github.com/gazebosim/gz-sim/pull/2435)

1. Optimize rendering sensor pose updates
* [Pull request #2425](https://github.com/gazebosim/gz-sim/pull/2425)

1. Remove a few extra zeros from some sdf files
* [Pull request #2426](https://github.com/gazebosim/gz-sim/pull/2426)

1. Use VERSION_GREATER_EQUAL in cmake logic
* [Pull request #2418](https://github.com/gazebosim/gz-sim/pull/2418)

1. Support mesh optimization when using AttachMeshShapeFeature
* [Pull request #2417](https://github.com/gazebosim/gz-sim/pull/2417)

1. Rephrase cmake comment about CMP0077
* [Pull request #2419](https://github.com/gazebosim/gz-sim/pull/2419)

1. Fix CMake warnings in Noble
* [Pull request #2397](https://github.com/gazebosim/gz-sim/pull/2397)

1. Update sensors with pending trigger immediately in Sensors system
* [Pull request #2408](https://github.com/gazebosim/gz-sim/pull/2408)

1. Add missing algorithm include
* [Pull request #2414](https://github.com/gazebosim/gz-sim/pull/2414)

1. Add Track and Follow options in gui EntityContextMenu
* [Pull request #2402](https://github.com/gazebosim/gz-sim/pull/2402)

1. ForceTorque system: improve readability
* [Pull request #2403](https://github.com/gazebosim/gz-sim/pull/2403)

1. LTA Dynamics System
* [Pull request #2241](https://github.com/gazebosim/gz-sim/pull/2241)

1. Remove Empty Test File
* [Pull request #2396](https://github.com/gazebosim/gz-sim/pull/2396)

1. Fix GCC/CMake warnings for Noble
* [Pull request #2375](https://github.com/gazebosim/gz-sim/pull/2375)

1. Fix warn unused variable in test
* [Pull request #2388](https://github.com/gazebosim/gz-sim/pull/2388)

1. Fix name of gz-fuel_tools in package.xml
* [Pull request #2386](https://github.com/gazebosim/gz-sim/pull/2386)

1. Add package.xml
* [Pull request #2337](https://github.com/gazebosim/gz-sim/pull/2337)

1. Fix namespace and class links in documentation references that use namespace `gz`
* [Pull request #2385](https://github.com/gazebosim/gz-sim/pull/2385)

1. Fix ModelPhotoShootTest test failures
* [Pull request #2294](https://github.com/gazebosim/gz-sim/pull/2294)

1. Enable StoreResolvedURIs when loading SDF
* [Pull request #2349](https://github.com/gazebosim/gz-sim/pull/2349)

1. Drop python3-disttutils from apt packages files
* [Pull request #2374](https://github.com/gazebosim/gz-sim/pull/2374)

1. Added example world for `DopplerVelocityLogSystem`
* [Pull request #2373](https://github.com/gazebosim/gz-sim/pull/2373)

1. Fix Gazebo/White and refactored MaterialParser
* [Pull request #2302](https://github.com/gazebosim/gz-sim/pull/2302)

1. Support for Gazebo materials
* [Pull request #2269](https://github.com/gazebosim/gz-sim/pull/2269)

### Gazebo Sim 8.3.0 (2024-04-11)

1. Use relative install paths for plugin shared libraries and gz-tools data
Expand Down
9 changes: 5 additions & 4 deletions examples/plugin/custom_sensor_system/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,11 @@ add_subdirectory(${sensors_clone_SOURCE_DIR}/examples/custom_sensor ${sensors_cl

add_library(${PROJECT_NAME} SHARED ${PROJECT_NAME}.cc)
target_link_libraries(${PROJECT_NAME}
PRIVATE gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER}
PRIVATE gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
PRIVATE gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER}
PRIVATE odometer
PRIVATE
gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER}
gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER}
odometer
)
target_include_directories(${PROJECT_NAME}
PUBLIC ${sensors_clone_SOURCE_DIR}/examples/custom_sensor)
5 changes: 3 additions & 2 deletions examples/standalone/gtest_setup/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,14 @@ set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR})
include(FetchContent)
FetchContent_Declare(
googletest
URL https://github.com/google/googletest/archive/609281088cfefc76f9d0ce82e1ff6c30cc3591e5.zip
DOWNLOAD_EXTRACT_TIMESTAMP TRUE
# Version 1.14. Use commit hash to prevent tag relocation
URL https://github.com/google/googletest/archive/f8d7d77c06936315286eb55f8de22cd23c188571.zip
)
set(gtest_force_shared_crt ON CACHE BOOL "" FORCE)
FetchContent_MakeAvailable(googletest)

enable_testing()
include(Dart)

# Generate tests
foreach(TEST_TARGET
Expand Down
78 changes: 78 additions & 0 deletions examples/worlds/lighter_than_air_blimp.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="blimp">

<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size>
<!-- Zero to run as fast as possible -->
<real_time_factor>1</real_time_factor>
</physics>

<gravity>0 0 -9.81</gravity>

<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>

<plugin
filename="gz-sim-buoyancy-system"
name="gz::sim::systems::Buoyancy">
<uniform_fluid_density>1.097</uniform_fluid_density>
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>
<include>
<uri>
https://fuel.gazebosim.org/1.0/hkotze/models/airship
</uri>
</include>
</world>
</sdf>
9 changes: 9 additions & 0 deletions include/gz/sim/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include <gz/math/Inertial.hh>
#include <gz/math/Matrix3.hh>
#include <gz/math/Matrix6.hh>
#include <gz/math/Pose3.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>
Expand Down Expand Up @@ -277,6 +278,14 @@ namespace gz
public: std::optional<math::Matrix3d> WorldInertiaMatrix(
const EntityComponentManager &_ecm) const;

/// \brief Get the fluid added mass matrix in the world frame.
/// \param[in] _ecm Entity-component manager.
/// \return Fluide added matrix in world frame, returns nullopt if link
/// does not have components components::Inertial and
/// components::WorldPose.
public: std::optional<math::Matrix6d> WorldFluidAddedMassMatrix(
const EntityComponentManager &_ecm) const;

/// \brief Get the rotational and translational kinetic energy of the
/// link with respect to the world frame.
/// \param[in] _ecm Entity-component manager.
Expand Down
7 changes: 7 additions & 0 deletions include/gz/sim/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -316,6 +316,13 @@ namespace gz
/// \return The loaded mesh or null if the mesh can not be loaded.
GZ_SIM_VISIBLE const common::Mesh *loadMesh(const sdf::Mesh &_meshSdf);

/// \brief Optimize input mesh.
/// \param[in] _meshSdf Mesh SDF DOM with mesh optimization parameters
/// \param[in] _mesh Input mesh to optimize.
/// \return The optimized mesh or null if the mesh can not be optimized.
GZ_SIM_VISIBLE const common::Mesh *optimizeMesh(const sdf::Mesh &_meshSdf,
const common::Mesh &_mesh);

/// \brief Environment variable holding resource paths.
const std::string kResourcePathEnv{"GZ_SIM_RESOURCE_PATH"};

Expand Down
1 change: 1 addition & 0 deletions include/gz/sim/components/Factory.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef GZ_SIM_COMPONENTS_FACTORY_HH_
#define GZ_SIM_COMPONENTS_FACTORY_HH_

#include <algorithm>
#include <cstdint>
#include <cstring>
#include <deque>
Expand Down
55 changes: 55 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>gz-sim8</name>
<version>8.4.0</version>
<description>Gazebo Sim : A Robotic Simulator</description>
<maintainer email="mjcarroll@intrinsic.ai">Michael Carroll</maintainer>
<license>Apache License 2.0</license>
<url type="website">https://github.com/gazebosim/gz-sim</url>

<buildtool_depend>cmake</buildtool_depend>

<depend>benchmark</depend>
<depend>glut</depend>
<depend>gz-cmake3</depend>
<depend>gz-common5</depend>
<depend>gz-fuel_tools9</depend>
<depend>gz-gui8</depend>
<depend>gz-math7</depend>
<depend>gz-msgs10</depend>
<depend>gz-physics7</depend>
<depend>gz-plugin2</depend>
<depend>gz-rendering8</depend>
<depend>gz-sensors8</depend>
<depend>gz-tools2</depend>
<depend>gz-transport13</depend>
<depend>gz-utils2</depend>
<depend>libfreeimage-dev</depend>
<depend>libglew-dev</depend>
<depend>libxi-dev</depend>
<depend>libxmu-dev</depend>
<depend>protobuf-dev</depend>
<depend>pybind11-dev</depend>
<depend>python3-distutils</depend>
<depend>qml-module-qt-labs-folderlistmodel</depend>
<depend>qml-module-qt-labs-settings</depend>
<depend>qml-module-qtgraphicaleffects</depend>
<depend>qml-module-qtquick-controls2</depend>
<depend>qml-module-qtquick-controls</depend>
<depend>qml-module-qtquick-dialogs</depend>
<depend>qml-module-qtquick-layouts</depend>
<depend>qml-module-qtquick2</depend>
<depend>qtbase5-dev</depend>
<depend>qtdeclarative5-dev</depend>
<depend>sdformat14</depend>
<depend>tinyxml2</depend>
<depend>uuid</depend>

<test_depend>xvfb</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>cmake</build_type>
</export>
</package>
3 changes: 1 addition & 2 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,6 @@ set (gtest_sources
SimulationRunner_TEST.cc
SystemLoader_TEST.cc
SystemManager_TEST.cc
System_TEST.cc
TestFixture_TEST.cc
Util_TEST.cc
World_TEST.cc
Expand Down Expand Up @@ -310,7 +309,7 @@ foreach(CMD_TEST
# to the PATH. This is done via the ENVIRONMENT_MODIFICATION that is only available
# since CMake 3.22. However, if an older CMake is used another trick to install the libraries
# beforehand
if (WIN32 AND CMAKE_VERSION STRGREATER "3.22")
if (WIN32 AND ${CMAKE_VERSION} VERSION_GREATER_EQUAL "3.22")
set_tests_properties(${CMD_TEST} PROPERTIES
ENVIRONMENT_MODIFICATION "PATH=path_list_prepend:${CMAKE_RUNTIME_OUTPUT_DIRECTORY}")
endif()
Expand Down
12 changes: 12 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -356,6 +356,18 @@ std::optional<math::Matrix3d> Link::WorldInertiaMatrix(
math::Inertiald(inertial->Data().MassMatrix(), comWorldPose).Moi());
}

std::optional<math::Matrix6d> Link::WorldFluidAddedMassMatrix(
const EntityComponentManager &_ecm) const
{
auto inertial = _ecm.Component<components::Inertial>(this->dataPtr->id);
auto worldPose = _ecm.Component<components::WorldPose>(this->dataPtr->id);

if (!worldPose || !inertial)
return std::nullopt;

return inertial->Data().FluidAddedMass();
}

//////////////////////////////////////////////////
std::optional<double> Link::WorldKineticEnergy(
const EntityComponentManager &_ecm) const
Expand Down
2 changes: 1 addition & 1 deletion src/ModelCommandAPI_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -657,7 +657,7 @@ TEST(ModelCommandAPI, GZ_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraSensor))
" - Lens intrinsics Fy: 277\n"
" - Lens intrinsics Cx: 160\n"
" - Lens intrinsics Cy: 120\n"
" - Lens intrinsics skew: 1\n"
" - Lens intrinsics skew: 0\n"
" - Visibility mask: 4294967295\n";
EXPECT_EQ(expectedOutput, output);
}
Expand Down
Loading

0 comments on commit 7b995af

Please sign in to comment.