Skip to content

Commit 1d3eee9

Browse files
authored
Merge pull request #2472 from gazebosim/scpeters/merge_8_main
Merge gz-sim8 ➡️ main
2 parents 0d89949 + 3c77346 commit 1d3eee9

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

56 files changed

+488
-159
lines changed

Changelog.md

+97
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,103 @@
44

55
## Gazebo Sim 8.x
66

7+
### Gazebo Sim 8.5.0 (2024-06-26)
8+
9+
1. Backport: Adding cone primitives
10+
* [Pull request #2404](https://github.com/gazebosim/gz-sim/pull/2404)
11+
12+
1. Permit to run gz sim -g on Windows
13+
* [Pull request #2382](https://github.com/gazebosim/gz-sim/pull/2382)
14+
15+
1. Parse voxel resolution SDF param when decomposing meshes
16+
* [Pull request #2445](https://github.com/gazebosim/gz-sim/pull/2445)
17+
18+
1. Fix model command api test
19+
* [Pull request #2444](https://github.com/gazebosim/gz-sim/pull/2444)
20+
21+
1. Add tutorial for using the Pose component
22+
* [Pull request #2219](https://github.com/gazebosim/gz-sim/pull/2219)
23+
24+
1. Do not update sensors if it a triggered sensor
25+
* [Pull request #2443](https://github.com/gazebosim/gz-sim/pull/2443)
26+
27+
### Gazebo Sim 8.4.0 (2024-06-12)
28+
29+
1. Add pause run tutorial
30+
* [Pull request #2383](https://github.com/gazebosim/gz-sim/pull/2383)
31+
32+
1. Fix warning message to show precise jump back in time duration
33+
* [Pull request #2435](https://github.com/gazebosim/gz-sim/pull/2435)
34+
35+
1. Optimize rendering sensor pose updates
36+
* [Pull request #2425](https://github.com/gazebosim/gz-sim/pull/2425)
37+
38+
1. Remove a few extra zeros from some sdf files
39+
* [Pull request #2426](https://github.com/gazebosim/gz-sim/pull/2426)
40+
41+
1. Use VERSION_GREATER_EQUAL in cmake logic
42+
* [Pull request #2418](https://github.com/gazebosim/gz-sim/pull/2418)
43+
44+
1. Support mesh optimization when using AttachMeshShapeFeature
45+
* [Pull request #2417](https://github.com/gazebosim/gz-sim/pull/2417)
46+
47+
1. Rephrase cmake comment about CMP0077
48+
* [Pull request #2419](https://github.com/gazebosim/gz-sim/pull/2419)
49+
50+
1. Fix CMake warnings in Noble
51+
* [Pull request #2397](https://github.com/gazebosim/gz-sim/pull/2397)
52+
53+
1. Update sensors with pending trigger immediately in Sensors system
54+
* [Pull request #2408](https://github.com/gazebosim/gz-sim/pull/2408)
55+
56+
1. Add missing algorithm include
57+
* [Pull request #2414](https://github.com/gazebosim/gz-sim/pull/2414)
58+
59+
1. Add Track and Follow options in gui EntityContextMenu
60+
* [Pull request #2402](https://github.com/gazebosim/gz-sim/pull/2402)
61+
62+
1. ForceTorque system: improve readability
63+
* [Pull request #2403](https://github.com/gazebosim/gz-sim/pull/2403)
64+
65+
1. LTA Dynamics System
66+
* [Pull request #2241](https://github.com/gazebosim/gz-sim/pull/2241)
67+
68+
1. Remove Empty Test File
69+
* [Pull request #2396](https://github.com/gazebosim/gz-sim/pull/2396)
70+
71+
1. Fix GCC/CMake warnings for Noble
72+
* [Pull request #2375](https://github.com/gazebosim/gz-sim/pull/2375)
73+
74+
1. Fix warn unused variable in test
75+
* [Pull request #2388](https://github.com/gazebosim/gz-sim/pull/2388)
76+
77+
1. Fix name of gz-fuel_tools in package.xml
78+
* [Pull request #2386](https://github.com/gazebosim/gz-sim/pull/2386)
79+
80+
1. Add package.xml
81+
* [Pull request #2337](https://github.com/gazebosim/gz-sim/pull/2337)
82+
83+
1. Fix namespace and class links in documentation references that use namespace `gz`
84+
* [Pull request #2385](https://github.com/gazebosim/gz-sim/pull/2385)
85+
86+
1. Fix ModelPhotoShootTest test failures
87+
* [Pull request #2294](https://github.com/gazebosim/gz-sim/pull/2294)
88+
89+
1. Enable StoreResolvedURIs when loading SDF
90+
* [Pull request #2349](https://github.com/gazebosim/gz-sim/pull/2349)
91+
92+
1. Drop python3-disttutils from apt packages files
93+
* [Pull request #2374](https://github.com/gazebosim/gz-sim/pull/2374)
94+
95+
1. Added example world for `DopplerVelocityLogSystem`
96+
* [Pull request #2373](https://github.com/gazebosim/gz-sim/pull/2373)
97+
98+
1. Fix Gazebo/White and refactored MaterialParser
99+
* [Pull request #2302](https://github.com/gazebosim/gz-sim/pull/2302)
100+
101+
1. Support for Gazebo materials
102+
* [Pull request #2269](https://github.com/gazebosim/gz-sim/pull/2269)
103+
7104
### Gazebo Sim 8.3.0 (2024-04-11)
8105

9106
1. Use relative install paths for plugin shared libraries and gz-tools data

examples/worlds/shapes.sdf

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<?xml version="1.0" ?>
2-
<sdf version="1.12">
2+
<sdf version="1.11">
33
<!--
44
Try moving a model using the command in the following CDATA block::
55
-->

include/gz/sim/components/Gravity.hh

+5
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,11 @@ namespace components
3636
/// \brief Store the gravity acceleration.
3737
using Gravity = Component<math::Vector3d, class GravityTag>;
3838
GZ_SIM_REGISTER_COMPONENT("gz_sim_components.Gravity", Gravity)
39+
40+
/// \brief Store the gravity acceleration.
41+
using GravityEnabled = Component<bool, class GravityEnabledTag>;
42+
GZ_SIM_REGISTER_COMPONENT(
43+
"gz_sim_components.GravityEnabled", GravityEnabled)
3944
}
4045
}
4146
}

src/Conversions.cc

+10-43
Original file line numberDiff line numberDiff line change
@@ -286,6 +286,10 @@ msgs::Geometry gz::sim::convert(const sdf::Geometry &_in)
286286
}
287287
}
288288
}
289+
else if (_in.Type() == sdf::GeometryType::EMPTY)
290+
{
291+
out.set_type(msgs::Geometry::EMPTY);
292+
}
289293
else
290294
{
291295
gzerr << "Geometry type [" << static_cast<int>(_in.Type())
@@ -902,7 +906,7 @@ msgs::Atmosphere gz::sim::convert(const sdf::Atmosphere &_in)
902906
out.set_type(msgs::Atmosphere::ADIABATIC);
903907
}
904908
// todo(anyone) add mass density to sdf::Atmosphere?
905-
// out.set_mass_density(_in.MassDensity());k
909+
// out.set_mass_density(_in.MassDensity());
906910

907911
return out;
908912
}
@@ -1735,15 +1739,7 @@ msgs::ParticleEmitter gz::sim::convert(const sdf::ParticleEmitter &_in)
17351739
}
17361740
}
17371741

1738-
/// \todo(nkoenig) Modify the particle_emitter.proto file to
1739-
/// have a topic field.
1740-
if (!_in.Topic().empty())
1741-
{
1742-
auto header = out.mutable_header()->add_data();
1743-
header->set_key("topic");
1744-
header->add_value(_in.Topic());
1745-
}
1746-
1742+
out.mutable_topic()->set_data(_in.Topic());
17471743
out.mutable_particle_scatter_ratio()->set_data(_in.ScatterRatio());
17481744
return out;
17491745
}
@@ -1798,15 +1794,8 @@ sdf::ParticleEmitter gz::sim::convert(const msgs::ParticleEmitter &_in)
17981794
out.SetColorRangeImage(_in.color_range_image().data());
17991795
if (_in.has_particle_scatter_ratio())
18001796
out.SetScatterRatio(_in.particle_scatter_ratio().data());
1801-
1802-
for (int i = 0; i < _in.header().data_size(); ++i)
1803-
{
1804-
auto data = _in.header().data(i);
1805-
if (data.key() == "topic" && data.value_size() > 0)
1806-
{
1807-
out.SetTopic(data.value(0));
1808-
}
1809-
}
1797+
if (_in.has_topic())
1798+
out.SetTopic(_in.topic().data());
18101799

18111800
return out;
18121801
}
@@ -1824,10 +1813,7 @@ msgs::Projector gz::sim::convert(const sdf::Projector &_in)
18241813
out.set_fov(_in.HorizontalFov().Radian());
18251814
out.set_texture(_in.Texture().empty() ? "" :
18261815
asFullPath(_in.Texture(), _in.FilePath()));
1827-
1828-
auto header = out.mutable_header()->add_data();
1829-
header->set_key("visibility_flags");
1830-
header->add_value(std::to_string(_in.VisibilityFlags()));
1816+
out.set_visibility_flags(_in.VisibilityFlags());
18311817

18321818
return out;
18331819
}
@@ -1844,26 +1830,7 @@ sdf::Projector gz::sim::convert(const msgs::Projector &_in)
18441830
out.SetHorizontalFov(math::Angle(_in.fov()));
18451831
out.SetTexture(_in.texture());
18461832
out.SetRawPose(msgs::Convert(_in.pose()));
1847-
1848-
/// \todo(anyone) add "visibility_flags" field to projector.proto
1849-
for (int i = 0; i < _in.header().data_size(); ++i)
1850-
{
1851-
auto data = _in.header().data(i);
1852-
if (data.key() == "visibility_flags" && data.value_size() > 0)
1853-
{
1854-
try
1855-
{
1856-
out.SetVisibilityFlags(std::stoul(data.value(0)));
1857-
}
1858-
catch (...)
1859-
{
1860-
gzerr << "Failed to parse projector <visibility_flags>: "
1861-
<< data.value(0) << ". Using default value: 0xFFFFFFFF."
1862-
<< std::endl;
1863-
out.SetVisibilityFlags(0xFFFFFFFF);
1864-
}
1865-
}
1866-
}
1833+
out.SetVisibilityFlags(_in.visibility_flags());
18671834

18681835
return out;
18691836
}

src/Conversions_TEST.cc

+12-8
Original file line numberDiff line numberDiff line change
@@ -1060,10 +1060,7 @@ TEST(Conversions, ParticleEmitter)
10601060
EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f),
10611061
msgs::Convert(emitterMsg.color_end()));
10621062
EXPECT_EQ("range_image", emitterMsg.color_range_image().data());
1063-
1064-
auto header = emitterMsg.header().data(0);
1065-
EXPECT_EQ("topic", header.key());
1066-
EXPECT_EQ("my_topic", header.value(0));
1063+
EXPECT_EQ("my_topic", emitterMsg.topic().data());
10671064

10681065
EXPECT_FLOAT_EQ(0.9f, emitterMsg.particle_scatter_ratio().data());
10691066

@@ -1113,10 +1110,7 @@ TEST(Conversions, Projector)
11131110
EXPECT_NEAR(30, projectorMsg.far_clip(), 1e-3);
11141111
EXPECT_NEAR(0.4, projectorMsg.fov(), 1e-3);
11151112
EXPECT_EQ("projector.png", projectorMsg.texture());
1116-
1117-
auto header = projectorMsg.header().data(0);
1118-
EXPECT_EQ("visibility_flags", header.key());
1119-
EXPECT_EQ(0xFF, std::stoul(header.value(0)));
1113+
EXPECT_EQ(0xFF, projectorMsg.visibility_flags());
11201114

11211115
// Convert the message back to SDF.
11221116
sdf::Projector projector2 = convert<sdf::Projector>(projectorMsg);
@@ -1222,3 +1216,13 @@ TEST(Conversions, MsgsPluginToSdf)
12221216
EXPECT_EQ(innerXml, sdfPlugins[1].Contents()[0]->ToString(""));
12231217
EXPECT_EQ(innerXml2, sdfPlugins[1].Contents()[1]->ToString(""));
12241218
}
1219+
1220+
/////////////////////////////////////////////////
1221+
TEST(Conversions, GeometryEmpty)
1222+
{
1223+
sdf::Geometry geometry;
1224+
geometry.SetType(sdf::GeometryType::EMPTY);
1225+
1226+
auto geometryMsg = convert<msgs::Geometry>(geometry);
1227+
EXPECT_EQ(msgs::Geometry::EMPTY, geometryMsg.type());
1228+
}

src/ModelCommandAPI_TEST.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -608,7 +608,7 @@ TEST(ModelCommandAPI, GZ_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraSensor))
608608
// Run without blocking.
609609
server.Run(false, 0, false);
610610

611-
// Tested command: gz model -m altimeter_mode -l link -s altimeter_sensor
611+
// Tested command: gz model -m rgbd_camera -l rgbd_camera_link -s rgbd_camera
612612
{
613613
const std::string cmd = kGzModelCommand
614614
+ "-m rgbd_camera -l rgbd_camera_link -s rgbd_camera";
@@ -657,7 +657,7 @@ TEST(ModelCommandAPI, GZ_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraSensor))
657657
" - Lens intrinsics Fy: 277\n"
658658
" - Lens intrinsics Cx: 160\n"
659659
" - Lens intrinsics Cy: 120\n"
660-
" - Lens intrinsics skew: 1\n"
660+
" - Lens intrinsics skew: 0\n"
661661
" - Visibility mask: 4294967295\n";
662662
EXPECT_EQ(expectedOutput, output);
663663
}

src/SdfEntityCreator.cc

+7
Original file line numberDiff line numberDiff line change
@@ -587,6 +587,13 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Link *_link)
587587
linkEntity, components::WindMode(_link->EnableWind()));
588588
}
589589

590+
if (!_link->EnableGravity())
591+
{
592+
// If disable gravity, create a GravityEnabled component to the entity
593+
this->dataPtr->ecm->CreateComponent(
594+
linkEntity, components::GravityEnabled(false));
595+
}
596+
590597
// Visuals
591598
for (uint64_t visualIndex = 0; visualIndex < _link->VisualCount();
592599
++visualIndex)

src/Util.cc

+7-7
Original file line numberDiff line numberDiff line change
@@ -892,18 +892,18 @@ const common::Mesh *optimizeMesh(const sdf::Mesh &_meshSdf,
892892
auto &meshManager = *common::MeshManager::Instance();
893893
std::size_t maxConvexHulls = 16u;
894894
std::size_t voxelResolution = 200000u;
895+
if (_meshSdf.ConvexDecomposition())
896+
{
897+
// limit max number of convex hulls to generate
898+
maxConvexHulls = _meshSdf.ConvexDecomposition()->MaxConvexHulls();
899+
voxelResolution = _meshSdf.ConvexDecomposition()->VoxelResolution();
900+
}
895901
if (_meshSdf.Optimization() == sdf::MeshOptimization::CONVEX_HULL)
896902
{
897903
/// create 1 convex hull for the whole submesh
898904
maxConvexHulls = 1u;
899905
}
900-
else if (_meshSdf.ConvexDecomposition())
901-
{
902-
// set convex decomposition params: max number of convex hulls
903-
// and voxel resolution
904-
maxConvexHulls = _meshSdf.ConvexDecomposition()->MaxConvexHulls();
905-
voxelResolution = _meshSdf.ConvexDecomposition()->VoxelResolution();
906-
}
906+
907907
// Check if MeshManager contains the decomposed mesh already. If not
908908
// add it to the MeshManager so we do not need to decompose it again.
909909
const std::string convexMeshName =

src/cmd/cmdsim.rb.in

-6
Original file line numberDiff line numberDiff line change
@@ -598,12 +598,6 @@ See https://github.com/gazebosim/gz-sim/issues/168 for more info."
598598
options['record-period'], options['seed'])
599599
# Otherwise run the gui
600600
else options['gui']
601-
if plugin.end_with? ".dll"
602-
puts "`gz sim` currently only works with the -s argument on Windows.
603-
See https://github.com/gazebosim/gz-sim/issues/168 for more info."
604-
exit(-1)
605-
end
606-
607601
ENV['RMT_PORT'] = '1501'
608602
Importer.runGui(options['gui_config'], options['file'],
609603
options['wait_gui'], options['render_engine_gui'],

src/systems/ackermann_steering/AckermannSteering.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -508,8 +508,8 @@ void AckermannSteering::PreUpdate(const UpdateInfo &_info,
508508
if (_info.dt < std::chrono::steady_clock::duration::zero())
509509
{
510510
gzwarn << "Detected jump back in time ["
511-
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
512-
<< "s]. System may not work properly." << std::endl;
511+
<< std::chrono::duration<double>(_info.dt).count()
512+
<< "s]. System may not work properly." << std::endl;
513513
}
514514

515515
// If the joints haven't been identified yet, look for them

src/systems/advanced_lift_drag/AdvancedLiftDrag.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -802,8 +802,8 @@ void AdvancedLiftDrag::PreUpdate(const UpdateInfo &_info,
802802
if (_info.dt < std::chrono::steady_clock::duration::zero())
803803
{
804804
gzwarn << "Detected jump back in time ["
805-
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
806-
<< "s]. System may not work properly." << std::endl;
805+
<< std::chrono::duration<double>(_info.dt).count()
806+
<< "s]. System may not work properly." << std::endl;
807807
}
808808

809809
if (!this->dataPtr->initialized)

src/systems/air_pressure/AirPressure.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -132,8 +132,8 @@ void AirPressure::PostUpdate(const UpdateInfo &_info,
132132
if (_info.dt < std::chrono::steady_clock::duration::zero())
133133
{
134134
gzwarn << "Detected jump back in time ["
135-
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
136-
<< "s]. System may not work properly." << std::endl;
135+
<< std::chrono::duration<double>(_info.dt).count()
136+
<< "s]. System may not work properly." << std::endl;
137137
}
138138

139139
this->dataPtr->CreateSensors(_ecm);

src/systems/air_speed/AirSpeed.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -134,8 +134,8 @@ void AirSpeed::PostUpdate(const UpdateInfo &_info,
134134
if (_info.dt < std::chrono::steady_clock::duration::zero())
135135
{
136136
gzwarn << "Detected jump back in time ["
137-
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
138-
<< "s]. System may not work properly." << std::endl;
137+
<< std::chrono::duration<double>(_info.dt).count()
138+
<< "s]. System may not work properly." << std::endl;
139139
}
140140

141141
this->dataPtr->CreateSensors(_ecm);

src/systems/altimeter/Altimeter.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -132,8 +132,8 @@ void Altimeter::PostUpdate(const UpdateInfo &_info,
132132
if (_info.dt < std::chrono::steady_clock::duration::zero())
133133
{
134134
gzwarn << "Detected jump back in time ["
135-
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
136-
<< "s]. System may not work properly." << std::endl;
135+
<< std::chrono::duration<double>(_info.dt).count()
136+
<< "s]. System may not work properly." << std::endl;
137137
}
138138

139139
this->dataPtr->CreateSensors(_ecm);

src/systems/apply_joint_force/ApplyJointForce.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -134,8 +134,8 @@ void ApplyJointForce::PreUpdate(const UpdateInfo &_info,
134134
if (_info.dt < std::chrono::steady_clock::duration::zero())
135135
{
136136
gzwarn << "Detected jump back in time ["
137-
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
138-
<< "s]. System may not work properly." << std::endl;
137+
<< std::chrono::duration<double>(_info.dt).count()
138+
<< "s]. System may not work properly." << std::endl;
139139
}
140140

141141
// If the joint hasn't been identified yet, look for it

0 commit comments

Comments
 (0)