Skip to content

Commit

Permalink
Merge pull request #2472 from gazebosim/scpeters/merge_8_main
Browse files Browse the repository at this point in the history
Merge gz-sim8 ➡️  main
  • Loading branch information
scpeters authored Jul 10, 2024
2 parents 0d89949 + 3c77346 commit 1d3eee9
Show file tree
Hide file tree
Showing 56 changed files with 488 additions and 159 deletions.
97 changes: 97 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,103 @@

## Gazebo Sim 8.x

### Gazebo Sim 8.5.0 (2024-06-26)

1. Backport: Adding cone primitives
* [Pull request #2404](https://github.com/gazebosim/gz-sim/pull/2404)

1. Permit to run gz sim -g on Windows
* [Pull request #2382](https://github.com/gazebosim/gz-sim/pull/2382)

1. Parse voxel resolution SDF param when decomposing meshes
* [Pull request #2445](https://github.com/gazebosim/gz-sim/pull/2445)

1. Fix model command api test
* [Pull request #2444](https://github.com/gazebosim/gz-sim/pull/2444)

1. Add tutorial for using the Pose component
* [Pull request #2219](https://github.com/gazebosim/gz-sim/pull/2219)

1. Do not update sensors if it a triggered sensor
* [Pull request #2443](https://github.com/gazebosim/gz-sim/pull/2443)

### 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
2 changes: 1 addition & 1 deletion examples/worlds/shapes.sdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<sdf version="1.12">
<sdf version="1.11">
<!--
Try moving a model using the command in the following CDATA block::
-->
Expand Down
5 changes: 5 additions & 0 deletions include/gz/sim/components/Gravity.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,11 @@ namespace components
/// \brief Store the gravity acceleration.
using Gravity = Component<math::Vector3d, class GravityTag>;
GZ_SIM_REGISTER_COMPONENT("gz_sim_components.Gravity", Gravity)

/// \brief Store the gravity acceleration.
using GravityEnabled = Component<bool, class GravityEnabledTag>;
GZ_SIM_REGISTER_COMPONENT(
"gz_sim_components.GravityEnabled", GravityEnabled)
}
}
}
Expand Down
53 changes: 10 additions & 43 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -286,6 +286,10 @@ msgs::Geometry gz::sim::convert(const sdf::Geometry &_in)
}
}
}
else if (_in.Type() == sdf::GeometryType::EMPTY)
{
out.set_type(msgs::Geometry::EMPTY);
}
else
{
gzerr << "Geometry type [" << static_cast<int>(_in.Type())
Expand Down Expand Up @@ -902,7 +906,7 @@ msgs::Atmosphere gz::sim::convert(const sdf::Atmosphere &_in)
out.set_type(msgs::Atmosphere::ADIABATIC);
}
// todo(anyone) add mass density to sdf::Atmosphere?
// out.set_mass_density(_in.MassDensity());k
// out.set_mass_density(_in.MassDensity());

return out;
}
Expand Down Expand Up @@ -1735,15 +1739,7 @@ msgs::ParticleEmitter gz::sim::convert(const sdf::ParticleEmitter &_in)
}
}

/// \todo(nkoenig) Modify the particle_emitter.proto file to
/// have a topic field.
if (!_in.Topic().empty())
{
auto header = out.mutable_header()->add_data();
header->set_key("topic");
header->add_value(_in.Topic());
}

out.mutable_topic()->set_data(_in.Topic());
out.mutable_particle_scatter_ratio()->set_data(_in.ScatterRatio());
return out;
}
Expand Down Expand Up @@ -1798,15 +1794,8 @@ sdf::ParticleEmitter gz::sim::convert(const msgs::ParticleEmitter &_in)
out.SetColorRangeImage(_in.color_range_image().data());
if (_in.has_particle_scatter_ratio())
out.SetScatterRatio(_in.particle_scatter_ratio().data());

for (int i = 0; i < _in.header().data_size(); ++i)
{
auto data = _in.header().data(i);
if (data.key() == "topic" && data.value_size() > 0)
{
out.SetTopic(data.value(0));
}
}
if (_in.has_topic())
out.SetTopic(_in.topic().data());

return out;
}
Expand All @@ -1824,10 +1813,7 @@ msgs::Projector gz::sim::convert(const sdf::Projector &_in)
out.set_fov(_in.HorizontalFov().Radian());
out.set_texture(_in.Texture().empty() ? "" :
asFullPath(_in.Texture(), _in.FilePath()));

auto header = out.mutable_header()->add_data();
header->set_key("visibility_flags");
header->add_value(std::to_string(_in.VisibilityFlags()));
out.set_visibility_flags(_in.VisibilityFlags());

return out;
}
Expand All @@ -1844,26 +1830,7 @@ sdf::Projector gz::sim::convert(const msgs::Projector &_in)
out.SetHorizontalFov(math::Angle(_in.fov()));
out.SetTexture(_in.texture());
out.SetRawPose(msgs::Convert(_in.pose()));

/// \todo(anyone) add "visibility_flags" field to projector.proto
for (int i = 0; i < _in.header().data_size(); ++i)
{
auto data = _in.header().data(i);
if (data.key() == "visibility_flags" && data.value_size() > 0)
{
try
{
out.SetVisibilityFlags(std::stoul(data.value(0)));
}
catch (...)
{
gzerr << "Failed to parse projector <visibility_flags>: "
<< data.value(0) << ". Using default value: 0xFFFFFFFF."
<< std::endl;
out.SetVisibilityFlags(0xFFFFFFFF);
}
}
}
out.SetVisibilityFlags(_in.visibility_flags());

return out;
}
Expand Down
20 changes: 12 additions & 8 deletions src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1060,10 +1060,7 @@ TEST(Conversions, ParticleEmitter)
EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f),
msgs::Convert(emitterMsg.color_end()));
EXPECT_EQ("range_image", emitterMsg.color_range_image().data());

auto header = emitterMsg.header().data(0);
EXPECT_EQ("topic", header.key());
EXPECT_EQ("my_topic", header.value(0));
EXPECT_EQ("my_topic", emitterMsg.topic().data());

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

Expand Down Expand Up @@ -1113,10 +1110,7 @@ TEST(Conversions, Projector)
EXPECT_NEAR(30, projectorMsg.far_clip(), 1e-3);
EXPECT_NEAR(0.4, projectorMsg.fov(), 1e-3);
EXPECT_EQ("projector.png", projectorMsg.texture());

auto header = projectorMsg.header().data(0);
EXPECT_EQ("visibility_flags", header.key());
EXPECT_EQ(0xFF, std::stoul(header.value(0)));
EXPECT_EQ(0xFF, projectorMsg.visibility_flags());

// Convert the message back to SDF.
sdf::Projector projector2 = convert<sdf::Projector>(projectorMsg);
Expand Down Expand Up @@ -1222,3 +1216,13 @@ TEST(Conversions, MsgsPluginToSdf)
EXPECT_EQ(innerXml, sdfPlugins[1].Contents()[0]->ToString(""));
EXPECT_EQ(innerXml2, sdfPlugins[1].Contents()[1]->ToString(""));
}

/////////////////////////////////////////////////
TEST(Conversions, GeometryEmpty)
{
sdf::Geometry geometry;
geometry.SetType(sdf::GeometryType::EMPTY);

auto geometryMsg = convert<msgs::Geometry>(geometry);
EXPECT_EQ(msgs::Geometry::EMPTY, geometryMsg.type());
}
4 changes: 2 additions & 2 deletions src/ModelCommandAPI_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -608,7 +608,7 @@ TEST(ModelCommandAPI, GZ_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraSensor))
// Run without blocking.
server.Run(false, 0, false);

// Tested command: gz model -m altimeter_mode -l link -s altimeter_sensor
// Tested command: gz model -m rgbd_camera -l rgbd_camera_link -s rgbd_camera
{
const std::string cmd = kGzModelCommand
+ "-m rgbd_camera -l rgbd_camera_link -s rgbd_camera";
Expand Down 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
7 changes: 7 additions & 0 deletions src/SdfEntityCreator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -587,6 +587,13 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Link *_link)
linkEntity, components::WindMode(_link->EnableWind()));
}

if (!_link->EnableGravity())
{
// If disable gravity, create a GravityEnabled component to the entity
this->dataPtr->ecm->CreateComponent(
linkEntity, components::GravityEnabled(false));
}

// Visuals
for (uint64_t visualIndex = 0; visualIndex < _link->VisualCount();
++visualIndex)
Expand Down
14 changes: 7 additions & 7 deletions src/Util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -892,18 +892,18 @@ const common::Mesh *optimizeMesh(const sdf::Mesh &_meshSdf,
auto &meshManager = *common::MeshManager::Instance();
std::size_t maxConvexHulls = 16u;
std::size_t voxelResolution = 200000u;
if (_meshSdf.ConvexDecomposition())
{
// limit max number of convex hulls to generate
maxConvexHulls = _meshSdf.ConvexDecomposition()->MaxConvexHulls();
voxelResolution = _meshSdf.ConvexDecomposition()->VoxelResolution();
}
if (_meshSdf.Optimization() == sdf::MeshOptimization::CONVEX_HULL)
{
/// create 1 convex hull for the whole submesh
maxConvexHulls = 1u;
}
else if (_meshSdf.ConvexDecomposition())
{
// set convex decomposition params: max number of convex hulls
// and voxel resolution
maxConvexHulls = _meshSdf.ConvexDecomposition()->MaxConvexHulls();
voxelResolution = _meshSdf.ConvexDecomposition()->VoxelResolution();
}

// Check if MeshManager contains the decomposed mesh already. If not
// add it to the MeshManager so we do not need to decompose it again.
const std::string convexMeshName =
Expand Down
6 changes: 0 additions & 6 deletions src/cmd/cmdsim.rb.in
Original file line number Diff line number Diff line change
Expand Up @@ -598,12 +598,6 @@ See https://github.com/gazebosim/gz-sim/issues/168 for more info."
options['record-period'], options['seed'])
# Otherwise run the gui
else options['gui']
if plugin.end_with? ".dll"
puts "`gz sim` currently only works with the -s argument on Windows.
See https://github.com/gazebosim/gz-sim/issues/168 for more info."
exit(-1)
end

ENV['RMT_PORT'] = '1501'
Importer.runGui(options['gui_config'], options['file'],
options['wait_gui'], options['render_engine_gui'],
Expand Down
4 changes: 2 additions & 2 deletions src/systems/ackermann_steering/AckermannSteering.cc
Original file line number Diff line number Diff line change
Expand Up @@ -508,8 +508,8 @@ void AckermannSteering::PreUpdate(const UpdateInfo &_info,
if (_info.dt < std::chrono::steady_clock::duration::zero())
{
gzwarn << "Detected jump back in time ["
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
<< std::chrono::duration<double>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
}

// If the joints haven't been identified yet, look for them
Expand Down
4 changes: 2 additions & 2 deletions src/systems/advanced_lift_drag/AdvancedLiftDrag.cc
Original file line number Diff line number Diff line change
Expand Up @@ -802,8 +802,8 @@ void AdvancedLiftDrag::PreUpdate(const UpdateInfo &_info,
if (_info.dt < std::chrono::steady_clock::duration::zero())
{
gzwarn << "Detected jump back in time ["
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
<< std::chrono::duration<double>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
}

if (!this->dataPtr->initialized)
Expand Down
4 changes: 2 additions & 2 deletions src/systems/air_pressure/AirPressure.cc
Original file line number Diff line number Diff line change
Expand Up @@ -132,8 +132,8 @@ void AirPressure::PostUpdate(const UpdateInfo &_info,
if (_info.dt < std::chrono::steady_clock::duration::zero())
{
gzwarn << "Detected jump back in time ["
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
<< std::chrono::duration<double>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
}

this->dataPtr->CreateSensors(_ecm);
Expand Down
4 changes: 2 additions & 2 deletions src/systems/air_speed/AirSpeed.cc
Original file line number Diff line number Diff line change
Expand Up @@ -134,8 +134,8 @@ void AirSpeed::PostUpdate(const UpdateInfo &_info,
if (_info.dt < std::chrono::steady_clock::duration::zero())
{
gzwarn << "Detected jump back in time ["
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
<< std::chrono::duration<double>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
}

this->dataPtr->CreateSensors(_ecm);
Expand Down
4 changes: 2 additions & 2 deletions src/systems/altimeter/Altimeter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -132,8 +132,8 @@ void Altimeter::PostUpdate(const UpdateInfo &_info,
if (_info.dt < std::chrono::steady_clock::duration::zero())
{
gzwarn << "Detected jump back in time ["
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
<< std::chrono::duration<double>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
}

this->dataPtr->CreateSensors(_ecm);
Expand Down
4 changes: 2 additions & 2 deletions src/systems/apply_joint_force/ApplyJointForce.cc
Original file line number Diff line number Diff line change
Expand Up @@ -134,8 +134,8 @@ void ApplyJointForce::PreUpdate(const UpdateInfo &_info,
if (_info.dt < std::chrono::steady_clock::duration::zero())
{
gzwarn << "Detected jump back in time ["
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
<< std::chrono::duration<double>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
}

// If the joint hasn't been identified yet, look for it
Expand Down
Loading

0 comments on commit 1d3eee9

Please sign in to comment.