Skip to content

Commit

Permalink
Merge branch 'sdf15' into patch-1
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters authored Mar 3, 2025
2 parents c0360af + 71fe504 commit 7f0a5c4
Show file tree
Hide file tree
Showing 11 changed files with 223 additions and 921 deletions.
940 changes: 44 additions & 896 deletions BUILD.bazel

Large diffs are not rendered by default.

13 changes: 7 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ if(COMMAND CMAKE_POLICY)
CMAKE_POLICY(SET CMP0004 NEW)
endif(COMMAND CMAKE_POLICY)

project (sdformat15 VERSION 15.1.1)
project (sdformat15 VERSION 15.2.0)

# The protocol version has nothing to do with the package version.
# It represents the current version of SDFormat implemented by the software
Expand Down Expand Up @@ -95,9 +95,6 @@ if (BUILD_SDF)
COMPONENTS Interpreter
OPTIONAL_COMPONENTS Development
)
if (NOT Python3_Development_FOUND)
GZ_BUILD_WARNING("Python development libraries are missing: Python interfaces are disabled.")
endif()
endif()

#################################################
Expand Down Expand Up @@ -151,8 +148,12 @@ if (BUILD_SDF)
add_subdirectory(sdf)
add_subdirectory(conf)
add_subdirectory(doc)
if (Python3_Development_FOUND AND NOT SKIP_PYBIND11)
add_subdirectory(python)
if (NOT SKIP_PYBIND11)
if (Python3_Development_FOUND)
add_subdirectory(python)
else()
message(WARNING "Python development libraries are missing: Python interfaces are disabled.")
endif()
endif()
endif(BUILD_SDF)

Expand Down
29 changes: 29 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,34 @@
## libsdformat 15.X

### libsdformat 15.2.0 (2025-02-12)

1. Add entry to Migration guide about the updated auto-inertia behavior
* [Pull request #1528](https://github.com/gazebosim/sdformat/pull/1528)

1. Add missed spec version 1.12 in the sdf_descriptions target
* [Pull request #1529](https://github.com/gazebosim/sdformat/pull/1529)

1. Resolve auto inertia based on input mass
* [Pull request #1513](https://github.com/gazebosim/sdformat/pull/1513)

1. ci.yml: run cppcheck, cpplint on noble
* [Pull request #1521](https://github.com/gazebosim/sdformat/pull/1521)

1. Add non-const overload for Root::Model() getter
* [Pull request #1524](https://github.com/gazebosim/sdformat/pull/1524)

1. Remove unncessary <iostream> includes
* [Pull request #1523](https://github.com/gazebosim/sdformat/pull/1523)

1. Don't reparse parent elements when cloning.
* [Pull request #1484](https://github.com/gazebosim/sdformat/pull/1484)

1. python bindings: get version from package.xml
* [Pull request #1504](https://github.com/gazebosim/sdformat/pull/1504)

1. Permit to test when building bindings separately from main library
* [Pull request #1509](https://github.com/gazebosim/sdformat/pull/1509)

### libsdformat 15.1.1 (2024-11-15)

1. **Baseline:** this includes all changes from 15.1.0 and earlier.
Expand Down
28 changes: 28 additions & 0 deletions include/sdf/ParserConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,21 @@ enum class ConfigureResolveAutoInertials
SAVE_CALCULATION_IN_ELEMENT,
};

/// \enum CalculateInertialFailurePolicyType
/// \brief Configuration options of how CalculateInertial() failures should
/// be handled.
enum class CalculateInertialFailurePolicyType
{
/// \brief If this value is used, failures of Geometry::CalculateInertial()
/// will result in a LINK_INERTIA_INVALID error with no inertial values
/// written.
ERR,

/// \brief If this value is used, failures of Geometry::CalculateInertial()
/// will result in default inertial values used and a WARNING.
WARN_AND_USE_DEFAULT_INERTIAL,
};

// Forward declare private data class.
class ParserConfigPrivate;

Expand Down Expand Up @@ -192,6 +207,19 @@ class SDFORMAT_VISIBLE ParserConfig
public: void SetCalculateInertialConfiguration(
ConfigureResolveAutoInertials _configuration);

/// \brief Get the current policy for handling failures of the
/// CalculateInertial() function. By default an error is reported.
/// \return Current set value of the CalculateInertialFailurePolicyType enum
public: CalculateInertialFailurePolicyType
CalculateInertialFailurePolicy() const;

/// \brief Set the policy for handling failures of the CalculateInertial()
/// function
/// \param[in] _policy The policy to set for handling failures of the
/// CalculateInertial() function
public: void SetCalculateInertialFailurePolicy(
CalculateInertialFailurePolicyType _policy);

/// \brief Registers a custom model parser.
/// \param[in] _modelParser Callback as described in
/// sdf/InterfaceElements.hh.
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>sdformat15</name>
<version>15.1.1</version>
<version>15.2.0</version>
<description>SDFormat is an XML file format that describes environments, objects, and robots
in a manner suitable for robotic applications</description>

Expand Down
2 changes: 1 addition & 1 deletion python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ set_target_properties(${BINDINGS_MODULE_NAME} PROPERTIES
configure_build_install_location(${BINDINGS_MODULE_NAME})

if (BUILD_TESTING AND NOT WIN32)
pybind11_add_module(sdformattest SHARED
pybind11_add_module(sdformattest MODULE
test/_gz_sdformattest_pybind11.cc
)

Expand Down
24 changes: 21 additions & 3 deletions src/Collision.cc
Original file line number Diff line number Diff line change
Expand Up @@ -322,9 +322,27 @@ void Collision::CalculateInertial(

if (!geomInertial)
{
_errors.push_back({ErrorCode::LINK_INERTIA_INVALID,
"Inertia Calculated for collision: " +
this->dataPtr->name + " is invalid."});
if (_config.CalculateInertialFailurePolicy() ==
CalculateInertialFailurePolicyType::WARN_AND_USE_DEFAULT_INERTIAL)
{
Error err(
sdf::ErrorCode::WARNING,
"Inertia Calculated for collision: " + this->dataPtr->name +
" is invalid, using default inertial values.");
enforceConfigurablePolicyCondition(_config.WarningsPolicy(), err,
_errors);

using namespace gz::math;
_inertial = Inertiald(MassMatrix3d(1, Vector3d::One, Vector3d::Zero),
Pose3d::Zero);
}
else if (_config.CalculateInertialFailurePolicy() ==
CalculateInertialFailurePolicyType::ERR)
{
_errors.push_back({ErrorCode::LINK_INERTIA_INVALID,
"Inertia Calculated for collision: " +
this->dataPtr->name + " is invalid."});
}
}
else
{
Expand Down
55 changes: 55 additions & 0 deletions src/Collision_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -398,6 +398,61 @@ TEST(DOMCollision, CalculateInertialPoseNotRelativeToLink)
EXPECT_EQ(expectedInertial.Pose(), link->Inertial().Pose());
}

/////////////////////////////////////////////////
TEST(DOMCollision, CollisionCalculateInertialFailurePolicy)
{
sdf::Collision collision;

sdf::ElementPtr sdf(new sdf::Element());
collision.Load(sdf);

const sdf::ParserConfig sdfParserConfig;
sdf::Geometry geom;
sdf::Mesh mesh;
geom.SetType(sdf::GeometryType::MESH);
geom.SetMeshShape(mesh);
collision.SetGeom(geom);

sdf::ParserConfig config;
sdf::Errors errors;
sdf::CustomInertiaCalcProperties inertiaCalcProps;

// Custom inertia calculator that returns null inertial
auto customMeshInertiaCalculator = [](
sdf::Errors &,
const sdf::CustomInertiaCalcProperties &)
-> std::optional<gz::math::Inertiald>
{
return std::nullopt;
};
config.RegisterCustomInertiaCalc(customMeshInertiaCalculator);

// With default inertial failure policy, there should be an error when the
// mesh inertial calculator returns null inertial values.
gz::math::Inertiald collisionInertial;
collision.CalculateInertial(errors, collisionInertial, config);
ASSERT_EQ(1u, errors.size()) << errors;
EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::LINK_INERTIA_INVALID);
const gz::math::Inertiald empty;
EXPECT_EQ(empty, collisionInertial);

// Set inertial failure policy to use default inertial values on failure and
// verify that there are no more errors.
errors.clear();
config.SetCalculateInertialFailurePolicy(
sdf::CalculateInertialFailurePolicyType::WARN_AND_USE_DEFAULT_INERTIAL);
collision.CalculateInertial(errors, collisionInertial, config);
EXPECT_TRUE(errors.empty()) << errors;

// Verify default inertial values are returned.
gz::math::Inertiald defaultInertial;
defaultInertial.SetMassMatrix(
gz::math::MassMatrix3d(1.0,
gz::math::Vector3d::One,
gz::math::Vector3d::Zero));
EXPECT_EQ(collisionInertial, defaultInertial);
}

/////////////////////////////////////////////////
TEST(DOMCollision, ToElement)
{
Expand Down
19 changes: 19 additions & 0 deletions src/ParserConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,11 @@ class sdf::ParserConfig::Implementation
/// to behave behave differently than the `warningsPolicy`.
public: std::optional<EnforcementPolicy> deprecatedElementsPolicy;

/// \brief Policy that is set for handling failures of the
/// CalculateInertial() function. By default errors are reported.
public: CalculateInertialFailurePolicyType calculateInertialFailurePolicy =
CalculateInertialFailurePolicyType::ERR;

/// \brief Configuration that is set for the CalculateInertial() function
/// By default it is set to SAVE_CALCULATION to preserve the behavior of
/// Root::Load() generating complete inertial information.
Expand Down Expand Up @@ -167,6 +172,20 @@ EnforcementPolicy ParserConfig::DeprecatedElementsPolicy() const
this->dataPtr->warningsPolicy);
}

/////////////////////////////////////////////////
CalculateInertialFailurePolicyType
ParserConfig::CalculateInertialFailurePolicy() const
{
return this->dataPtr->calculateInertialFailurePolicy;
}

/////////////////////////////////////////////////
void ParserConfig::SetCalculateInertialFailurePolicy(
CalculateInertialFailurePolicyType _policy)
{
this->dataPtr->calculateInertialFailurePolicy = _policy;
}

/////////////////////////////////////////////////
ConfigureResolveAutoInertials
ParserConfig::CalculateInertialConfiguration() const
Expand Down
8 changes: 8 additions & 0 deletions src/ParserConfig_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,14 @@ TEST(ParserConfig, Construction)
EXPECT_EQ(sdf::ConfigureResolveAutoInertials::SAVE_CALCULATION_IN_ELEMENT,
config.CalculateInertialConfiguration());

EXPECT_EQ(sdf::CalculateInertialFailurePolicyType::ERR,
config.CalculateInertialFailurePolicy());
config.SetCalculateInertialFailurePolicy(
sdf::CalculateInertialFailurePolicyType::WARN_AND_USE_DEFAULT_INERTIAL);
EXPECT_EQ(
sdf::CalculateInertialFailurePolicyType::WARN_AND_USE_DEFAULT_INERTIAL,
config.CalculateInertialFailurePolicy());

EXPECT_FALSE(config.URDFPreserveFixedJoint());
EXPECT_FALSE(config.StoreResolvedURIs());
}
Expand Down
24 changes: 10 additions & 14 deletions test/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -347,7 +347,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Pose3",
"@gz-math",
],
)

Expand Down Expand Up @@ -444,7 +444,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Pose3",
"@gz-math",
],
)

Expand All @@ -458,7 +458,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Color",
"@gz-math",
],
)

Expand Down Expand Up @@ -504,7 +504,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Color",
"@gz-math",
],
)

Expand Down Expand Up @@ -538,8 +538,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Pose3",
"@gz-math//:Vector3",
"@gz-math",
],
)

Expand Down Expand Up @@ -576,8 +575,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Pose3",
"@gz-math//:Vector3",
"@gz-math",
],
)

Expand Down Expand Up @@ -663,7 +661,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Vector3",
"@gz-math",
],
)

Expand Down Expand Up @@ -722,9 +720,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Angle",
"@gz-math//:Pose3",
"@gz-math//:Vector3",
"@gz-math",
],
)

Expand Down Expand Up @@ -770,7 +766,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Vector3",
"@gz-math",
],
)

Expand Down Expand Up @@ -835,7 +831,7 @@ cc_test(
"//:sdformat",
"@googletest//:gtest",
"@googletest//:gtest_main",
"@gz-math//:Color",
"@gz-math",
],
)

Expand Down

0 comments on commit 7f0a5c4

Please sign in to comment.