Skip to content

Commit

Permalink
Merge pull request #2422 from gazebosim/scpeters/merge_8_main
Browse files Browse the repository at this point in the history
Merge gz-sim8 ➡️  main
  • Loading branch information
iche033 committed May 31, 2024
2 parents 3c2a3ce + cd068de commit 6ab114f
Show file tree
Hide file tree
Showing 22 changed files with 1,523 additions and 54 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
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-sim9_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
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-sim9</name>
<version>9.0.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-cmake4</depend>
<depend>gz-common6</depend>
<depend>gz-fuel_tools10</depend>
<depend>gz-gui9</depend>
<depend>gz-math8</depend>
<depend>gz-msgs11</depend>
<depend>gz-physics8</depend>
<depend>gz-plugin3</depend>
<depend>gz-rendering9</depend>
<depend>gz-sensors9</depend>
<depend>gz-tools2</depend>
<depend>gz-transport14</depend>
<depend>gz-utils3</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>sdformat15</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>
1 change: 0 additions & 1 deletion 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
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
27 changes: 0 additions & 27 deletions src/System_TEST.cc

This file was deleted.

Loading

0 comments on commit 6ab114f

Please sign in to comment.