Skip to content

Commit 8435399

Browse files
authored
Merge branch 'gz-sim10' into jasmeet/led_plugin_v2
2 parents 1cbb610 + 9deb93c commit 8435399

33 files changed

Lines changed: 1897 additions & 337 deletions

BUILD.bazel

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -853,6 +853,7 @@ gz_sim_system_libraries(
853853
"src/systems/hydrodynamics/**/*.cc",
854854
"src/systems/hydrodynamics/**/*.hh",
855855
],
856+
exclude = ["src/systems/hydrodynamics/*_TEST.cc"],
856857
),
857858
so_lib_name = "gz-sim-hydrodynamics-system.so",
858859
static_lib_name = "gz-sim-hydrodynamics-system-static",
@@ -867,6 +868,22 @@ gz_sim_system_libraries(
867868
],
868869
)
869870

871+
hydrodynamics_test_sources = glob([
872+
"src/systems/hydrodynamics/*_TEST.cc",
873+
])
874+
875+
[cc_test(
876+
name = src.replace("/", "_").replace(".cc", "").replace("src_", ""),
877+
srcs = [src],
878+
copts = ["-Wno-private-header"],
879+
deps = [
880+
":gz-sim-hydrodynamics-system-static",
881+
"@eigen",
882+
"@googletest//:gtest",
883+
"@googletest//:gtest_main",
884+
],
885+
) for src in hydrodynamics_test_sources]
886+
870887
gz_sim_system_libraries(
871888
srcs = glob(
872889
[

CMakeLists.txt

Lines changed: 16 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -289,20 +289,28 @@ configure_file(${CMAKE_SOURCE_DIR}/tutorials.md.in ${CMAKE_BINARY_DIR}/tutorials
289289
configure_file(${CMAKE_SOURCE_DIR}/tools/desktop/gz-sim.desktop.in ${CMAKE_BINARY_DIR}/gz-sim${PROJECT_VERSION_MAJOR}.desktop)
290290
configure_file(${CMAKE_SOURCE_DIR}/tools/desktop/gz-logo.svg.in ${CMAKE_BINARY_DIR}/gz-logo${PROJECT_VERSION_MAJOR}.svg)
291291

292+
set(gz_sim_doxygen_tagfiles
293+
"${GZ-MATH_DOXYGEN_TAGFILE} = ${GZ-MATH_API_URL}"
294+
"${GZ-MSGS_DOXYGEN_TAGFILE} = ${GZ-MSGS_API_URL}"
295+
"${GZ-PHYSICS_DOXYGEN_TAGFILE} = ${GZ-PHYSICS_API_URL}"
296+
"${GZ-PLUGIN_DOXYGEN_TAGFILE} = ${GZ-PLUGIN_API_URL}"
297+
"${GZ-TRANSPORT_DOXYGEN_TAGFILE} = ${GZ-TRANSPORT_API_URL}"
298+
"${GZ-SENSORS_DOXYGEN_TAGFILE} = ${GZ-SENSORS_API_URL}"
299+
"${GZ-COMMON_DOXYGEN_TAGFILE} = ${GZ-COMMON_API_URL}"
300+
)
301+
302+
if(EXISTS "${GZ-GUI_DOXYGEN_TAGFILE}")
303+
list(APPEND gz_sim_doxygen_tagfiles
304+
"${GZ-GUI_DOXYGEN_TAGFILE} = ${GZ-GUI_API_URL}")
305+
endif()
306+
292307
gz_create_docs(
293308
API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md"
294309
TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md"
295310
ADDITIONAL_INPUT_DIRS "${CMAKE_SOURCE_DIR}/src/systems ${CMAKE_SOURCE_DIR}/src/gui/plugins"
296311
IMAGE_PATH_DIRS "${CMAKE_SOURCE_DIR}/tutorials/files"
297312
TAGFILES
298-
"${GZ-MATH_DOXYGEN_TAGFILE} = ${GZ-MATH_API_URL}"
299-
"${GZ-MSGS_DOXYGEN_TAGFILE} = ${GZ-MSGS_API_URL}"
300-
"${GZ-PHYSICS_DOXYGEN_TAGFILE} = ${GZ-PHYSICS_API_URL}"
301-
"${GZ-PLUGIN_DOXYGEN_TAGFILE} = ${GZ-PLUGIN_API_URL}"
302-
"${GZ-TRANSPORT_DOXYGEN_TAGFILE} = ${GZ-TRANSPORT_API_URL}"
303-
"${GZ-SENSORS_DOXYGEN_TAGFILE} = ${GZ-SENSORS_API_URL}"
304-
"${GZ-COMMON_DOXYGEN_TAGFILE} = ${GZ-COMMON_API_URL}"
305-
"${GZ-GUI_DOXYGEN_TAGFILE} = ${GZ-GUI_API_URL}"
313+
${gz_sim_doxygen_tagfiles}
306314
)
307315

308316
if(TARGET doc)

MODULE.bazel

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ bazel_dep(name = "tinyxml2", version = "10.0.0")
1717
bazel_dep(name = "rules_gazebo", version = "0.0.6")
1818
bazel_dep(name = "gz-common", version = "7.1.0")
1919
bazel_dep(name = "gz-fuel-tools", version = "11.0.0")
20-
bazel_dep(name = "gz-math", version = "9.0.0")
20+
bazel_dep(name = "gz-math", version = "9.1.0")
2121
bazel_dep(name = "gz-msgs", version = "12.0.0")
2222
bazel_dep(name = "gz-physics", version = "9.0.0")
2323
bazel_dep(name = "gz-plugin", version = "4.0.0")

Migration.md

Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,81 @@ release will remove the deprecated code.
77

88
## Gazebo Sim 9.x to 10.0
99

10+
* **Removals**
11+
* **Hydrodynamics**: The `<water_density>` SDF parameter has been removed.
12+
It was loaded but never used in any computation because the stability
13+
derivatives (e.g. `<xUabsU>`, `<yVabsV>`) already incorporate fluid
14+
density. Existing SDF files that specify `<water_density>` will continue
15+
to load without error; the parameter is simply ignored.
16+
17+
* **Deprecations**
18+
* **Hydrodynamics**: Added mass via plugin parameters (`<xDotU>`,
19+
`<yDotV>`, `<zDotW>`, `<kDotP>`, `<mDotQ>`, `<nDotR>`, and all
20+
cross terms `<*Dot*>`) is deprecated **when using the DART physics
21+
engine**. The explicit integration used by this path is conditionally
22+
stable. These parameters remain required for other physics engines
23+
(Bullet, MuJoCo) that do not support native added mass.
24+
25+
When using the DART physics engine, use the SDF `<fluid_added_mass>`
26+
tag on the link's `<inertial>` element instead. The physics engine
27+
integrates added mass implicitly (unconditionally stable) and
28+
computes the full non-diagonal Coriolis matrix automatically.
29+
30+
Other physics engines (Bullet, MuJoCo) do not support native added
31+
mass, so plugin-based parameters remain the only option for those
32+
backends.
33+
34+
**Warning**: Do not set added mass in both `<fluid_added_mass>` and
35+
the plugin simultaneously. If both are active, forces are
36+
double-counted. The plugin now emits an error if this is detected.
37+
38+
**Migration example (DART)** — replace:
39+
```xml
40+
<plugin filename="gz-sim-hydrodynamics-system"
41+
name="gz::sim::systems::Hydrodynamics">
42+
<link_name>base_link</link_name>
43+
<xDotU>-4.876161</xDotU>
44+
<yDotV>-126.324739</yDotV>
45+
<zDotW>-126.324739</zDotW>
46+
<mDotQ>-33.46</mDotQ>
47+
<nDotR>-33.46</nDotR>
48+
<xUabsU>-6.2282</xUabsU>
49+
...
50+
</plugin>
51+
```
52+
53+
with:
54+
```xml
55+
<link name="base_link">
56+
<inertial>
57+
<fluid_added_mass>
58+
<xx>4.876161</xx>
59+
<yy>126.324739</yy>
60+
<zz>126.324739</zz>
61+
<qq>33.46</qq>
62+
<rr>33.46</rr>
63+
</fluid_added_mass>
64+
</inertial>
65+
</link>
66+
67+
<plugin filename="gz-sim-hydrodynamics-system"
68+
name="gz::sim::systems::Hydrodynamics">
69+
<link_name>base_link</link_name>
70+
<disable_added_mass>true</disable_added_mass>
71+
<xUabsU>-6.2282</xUabsU>
72+
...
73+
</plugin>
74+
```
75+
76+
Note that `<fluid_added_mass>` uses positive values (physical
77+
convention), while the legacy `<xDotU>` parameters use negative
78+
values (Fossen sign convention). See
79+
http://sdformat.org/spec?ver=1.11&elem=link#inertial_fluid_added_mass
80+
81+
When both `<fluid_added_mass>` and an ocean current are active, the
82+
plugin automatically corrects the Coriolis force to use the velocity
83+
relative to the fluid rather than the absolute velocity.
84+
1085
* Upgraded GUI framework from Qt5 to Qt6. All GUI plugins distributed by gz-sim
1186
have been migrated. This upgrade affects all users' custom Gazebo GUI plugins.
1287
Please see the

include/gz/sim/detail/EntityComponentManager.hh

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -264,9 +264,9 @@ std::vector<Entity> EntityComponentManager::ChildrenByComponents(Entity _parent,
264264

265265
// Iterate over entities
266266
std::vector<Entity> result;
267-
for (const Entity entity : view->Entities())
267+
for (const auto &child : children)
268268
{
269-
if (children.find(entity) == children.end())
269+
if (view->Entities().find(child.first) == view->Entities().end())
270270
{
271271
continue;
272272
}
@@ -278,7 +278,7 @@ std::vector<Entity> EntityComponentManager::ChildrenByComponents(Entity _parent,
278278
{
279279
auto entityComponent = this->Component<
280280
std::remove_cv_t<std::remove_reference_t<
281-
decltype(_desiredComponent)>>>(entity);
281+
decltype(_desiredComponent)>>>(child.first);
282282

283283
if (*entityComponent != _desiredComponent)
284284
{
@@ -288,7 +288,7 @@ std::vector<Entity> EntityComponentManager::ChildrenByComponents(Entity _parent,
288288

289289
if (!different)
290290
{
291-
result.push_back(entity);
291+
result.push_back(child.first);
292292
}
293293
}
294294

src/Joint.cc

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -170,9 +170,7 @@ Entity Joint::SensorByName(const EntityComponentManager &_ecm,
170170
//////////////////////////////////////////////////
171171
std::vector<Entity> Joint::Sensors(const EntityComponentManager &_ecm) const
172172
{
173-
return _ecm.EntitiesByComponents(
174-
components::ParentEntity(this->dataPtr->id),
175-
components::Sensor());
173+
return _ecm.ChildrenByComponents(this->dataPtr->id, components::Sensor());
176174
}
177175

178176
//////////////////////////////////////////////////

src/Link.cc

Lines changed: 3 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -151,25 +151,19 @@ Entity Link::VisualByName(const EntityComponentManager &_ecm,
151151
//////////////////////////////////////////////////
152152
std::vector<Entity> Link::Collisions(const EntityComponentManager &_ecm) const
153153
{
154-
return _ecm.EntitiesByComponents(
155-
components::ParentEntity(this->dataPtr->id),
156-
components::Collision());
154+
return _ecm.ChildrenByComponents(this->dataPtr->id, components::Collision());
157155
}
158156

159157
//////////////////////////////////////////////////
160158
std::vector<Entity> Link::Sensors(const EntityComponentManager &_ecm) const
161159
{
162-
return _ecm.EntitiesByComponents(
163-
components::ParentEntity(this->dataPtr->id),
164-
components::Sensor());
160+
return _ecm.ChildrenByComponents(this->dataPtr->id, components::Sensor());
165161
}
166162

167163
//////////////////////////////////////////////////
168164
std::vector<Entity> Link::Visuals(const EntityComponentManager &_ecm) const
169165
{
170-
return _ecm.EntitiesByComponents(
171-
components::ParentEntity(this->dataPtr->id),
172-
components::Visual());
166+
return _ecm.ChildrenByComponents(this->dataPtr->id, components::Visual());
173167
}
174168

175169
//////////////////////////////////////////////////

src/Model.cc

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -161,24 +161,24 @@ Entity Model::ModelByName(const EntityComponentManager &_ecm,
161161
//////////////////////////////////////////////////
162162
std::vector<Entity> Model::Joints(const EntityComponentManager &_ecm) const
163163
{
164-
return _ecm.EntitiesByComponents(
165-
components::ParentEntity(this->dataPtr->id),
164+
return _ecm.ChildrenByComponents(
165+
this->dataPtr->id,
166166
components::Joint());
167167
}
168168

169169
//////////////////////////////////////////////////
170170
std::vector<Entity> Model::Links(const EntityComponentManager &_ecm) const
171171
{
172-
return _ecm.EntitiesByComponents(
173-
components::ParentEntity(this->dataPtr->id),
172+
return _ecm.ChildrenByComponents(
173+
this->dataPtr->id,
174174
components::Link());
175175
}
176176

177177
//////////////////////////////////////////////////
178178
std::vector<Entity> Model::Models(const EntityComponentManager &_ecm) const
179179
{
180-
return _ecm.EntitiesByComponents(
181-
components::ParentEntity(this->dataPtr->id),
180+
return _ecm.ChildrenByComponents(
181+
this->dataPtr->id,
182182
components::Model());
183183
}
184184

src/SimulationRunner.cc

Lines changed: 82 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,16 @@
6666
#include "LevelManager.hh"
6767
#include "SdfGenerator.hh"
6868

69+
#ifdef _WIN32
70+
#ifndef NOMINMAX
71+
#define NOMINMAX
72+
#endif
73+
#ifndef WIN32_LEAN_AND_MEAN
74+
#define WIN32_LEAN_AND_MEAN
75+
#endif
76+
#include <windows.h>
77+
#endif
78+
6979
using namespace gz;
7080
using namespace sim;
7181

@@ -103,6 +113,34 @@ struct MaybeGilScopedRelease
103113

104114
}
105115

116+
#ifdef _WIN32
117+
namespace gz
118+
{
119+
namespace sim
120+
{
121+
inline namespace GZ_SIM_VERSION_NAMESPACE {
122+
// Utility class to store the windows HANDLE variable and close
123+
// the handle using RAII. This class also hides the HANDLE
124+
// type from the global header files.
125+
class SimulationRunnerWinHandleStorage
126+
{
127+
private: HANDLE handleStorage{NULL};
128+
129+
public: HANDLE handle() { return handleStorage; }
130+
131+
public: SimulationRunnerWinHandleStorage(HANDLE h) : handleStorage(h) {}
132+
133+
public: ~SimulationRunnerWinHandleStorage() {
134+
if (handleStorage != NULL)
135+
{
136+
CloseHandle(handleStorage);
137+
}
138+
}
139+
};
140+
}
141+
}
142+
}
143+
#endif
106144

107145
//////////////////////////////////////////////////
108146
SimulationRunner::SimulationRunner(const sdf::World &_world,
@@ -182,6 +220,16 @@ SimulationRunner::SimulationRunner(const sdf::World &_world,
182220
);
183221
this->currentInfo.simTime = this->simTimeEpoch;
184222

223+
#ifdef _WIN32
224+
HANDLE winPrecisionTimerHandle = CreateWaitableTimerExA(NULL, NULL,
225+
CREATE_WAITABLE_TIMER_HIGH_RESOLUTION, TIMER_ALL_ACCESS);
226+
if (winPrecisionTimerHandle != NULL)
227+
{
228+
winPrecisionTimer = std::make_unique<SimulationRunnerWinHandleStorage>(
229+
winPrecisionTimerHandle);
230+
}
231+
#endif
232+
185233
// World control
186234
transport::NodeOptions opts;
187235
std::string ns{"/world/" + this->worldName};
@@ -913,14 +961,45 @@ bool SimulationRunner::Run(const uint64_t _iterations)
913961
// larger than the typical OS + CPU C-state latency.
914962
constexpr auto kSpinThreshold = 200us;
915963

964+
auto now = std::chrono::steady_clock::now();
965+
916966
// If the scheduled update time is in the future...
917-
if (nextUpdateTime > std::chrono::steady_clock::now())
967+
if (nextUpdateTime > now)
918968
{
919969
// ...sleep until we are close to the target time.
920970
auto sleepTarget = nextUpdateTime - kSpinThreshold;
921-
if (sleepTarget > std::chrono::steady_clock::now())
971+
if (sleepTarget > now)
922972
{
973+
#ifndef _WIN32
923974
std::this_thread::sleep_until(sleepTarget);
975+
#else
976+
if (winPrecisionTimer)
977+
{
978+
auto sleepTargetDuration =
979+
std::chrono::duration_cast<std::chrono::microseconds>(
980+
sleepTarget - now);
981+
LARGE_INTEGER due_time;
982+
memset(&due_time, 0, sizeof(due_time));
983+
// Positive durations are absolute, while negative durations
984+
// are relative in 10 us intervals.
985+
// The absolute time uses the non-precision system clock so we
986+
// need to use relative time.
987+
due_time.QuadPart = -sleepTargetDuration.count() * 10;
988+
if (SetWaitableTimer(winPrecisionTimer->handle(), &due_time, 0,
989+
NULL, NULL, FALSE) != TRUE)
990+
{
991+
gzerr << "Could not SetWaitableTimer" << std::endl;
992+
}
993+
else
994+
{
995+
WaitForSingleObject(winPrecisionTimer->handle(), INFINITE);
996+
}
997+
}
998+
else
999+
{
1000+
std::this_thread::sleep_until(sleepTarget);
1001+
}
1002+
#endif
9241003
}
9251004

9261005
// ...then busy-wait for the final moments for precision.
@@ -931,7 +1010,7 @@ bool SimulationRunner::Run(const uint64_t _iterations)
9311010
}
9321011

9331012
// Schedule the next update time.
934-
auto now = std::chrono::steady_clock::now();
1013+
now = std::chrono::steady_clock::now();
9351014
nextUpdateTime += this->updatePeriod;
9361015
if (nextUpdateTime < now)
9371016
{

0 commit comments

Comments
 (0)