Skip to content

Commit

Permalink
update doc add comments
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 committed Dec 10, 2024
1 parent bcea463 commit cf4d77b
Show file tree
Hide file tree
Showing 3 changed files with 32 additions and 15 deletions.
3 changes: 2 additions & 1 deletion include/sdf/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -356,7 +356,8 @@ namespace sdf
/// If mass is not provided by the user, the inertial values will be
/// determined based on either link density or collision density if
/// explicitly set. Otherwise, if mass is specified, the inertia matrix
/// will be scaled to match the desired mass.
/// will be scaled to match the desired mass, while respecting
/// the ratio of density values between collisions.
/// \param[out] _errors A vector of Errors object. Each object
/// would contain an error code and an error message.
/// \param[in] _config Custom parser configuration
Expand Down
20 changes: 13 additions & 7 deletions python/test/pyLink_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -482,13 +482,15 @@ def test_resolveauto_inertialsWithMultipleCollisions(self):
self.assertEqual(Vector3d(2.013513, 2.013513, 0.72603),
link.inertial().mass_matrix().diagonal_moments())

def test_resolveauto_inertialsWithMass(self):
def test_inertial_values_given_with_auto_set_to_true(self):
# The inertia matrix is specified but should be ignored.
# <mass> is not speicifed so the inertial values should be computed
# based on the collision density value.
sdf = "<?xml version=\"1.0\"?>" + \
"<sdf version=\"1.11\">" + \
" <model name='compound_model'>" + \
" <link name='compound_link'>" + \
" <inertial auto='True'>" + \
" <mass>4.0</mass>" + \
" <pose>1 1 1 2 2 2</pose>" + \
" <inertia>" + \
" <ixx>1</ixx>" + \
Expand Down Expand Up @@ -519,17 +521,21 @@ def test_resolveauto_inertialsWithMass(self):
root.resolve_auto_inertials(errors, sdfParserConfig)
self.assertEqual(len(errors), 0)

self.assertEqual(4.0, link.inertial().mass_matrix().mass())
self.assertNotEqual(4.0, link.inertial().mass_matrix().mass())
self.assertEqual(Pose3d.ZERO, link.inertial().pose())
self.assertEqual(Vector3d(0.66666, 0.66666, 0.66666),
self.assertEqual(Vector3d(0.33333, 0.33333, 0.33333),
link.inertial().mass_matrix().diagonal_moments())

def test_inertial_values_given_with_auto_set_to_true(self):
def test_resolveauto_inertialsWithMass(self):
# The inertia matrix is specified but should be ignored.
# <mass> is speicifed - the auto computed inertial values should
# be scaled based on the desired mass.
sdf = "<?xml version=\"1.0\"?>" + \
"<sdf version=\"1.11\">" + \
" <model name='compound_model'>" + \
" <link name='compound_link'>" + \
" <inertial auto='True'>" + \
" <mass>4.0</mass>" + \
" <pose>1 1 1 2 2 2</pose>" + \
" <inertia>" + \
" <ixx>1</ixx>" + \
Expand Down Expand Up @@ -560,9 +566,9 @@ def test_inertial_values_given_with_auto_set_to_true(self):
root.resolve_auto_inertials(errors, sdfParserConfig)
self.assertEqual(len(errors), 0)

self.assertNotEqual(4.0, link.inertial().mass_matrix().mass())
self.assertEqual(4.0, link.inertial().mass_matrix().mass())
self.assertEqual(Pose3d.ZERO, link.inertial().pose())
self.assertEqual(Vector3d(0.33333, 0.33333, 0.33333),
self.assertEqual(Vector3d(0.66666, 0.66666, 0.66666),
link.inertial().mass_matrix().diagonal_moments())

def test_resolveauto_inertialsCalledWithAutoFalse(self):
Expand Down
24 changes: 17 additions & 7 deletions src/Link_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -725,14 +725,17 @@ TEST(DOMLink, ResolveAutoInertialsWithMultipleCollisions)
}

/////////////////////////////////////////////////
TEST(DOMLink, ResolveAutoInertialsWithMass)
TEST(DOMLink, InertialValuesGivenWithAutoSetToTrue)
{
// A model with link inertial auto set to true.
// The inertia matrix is specified but should be ignored.
// <mass> is not speicifed so the inertial values should be computed
// based on the collision density value.
std::string sdf = "<?xml version=\"1.0\"?>"
"<sdf version=\"1.11\">"
" <model name='compound_model'>"
" <link name='compound_link'>"
" <inertial auto='true'>"
" <mass>4.0</mass>"
" <pose>1 1 1 2 2 2</pose>"
" <inertia>"
" <ixx>1</ixx>"
Expand Down Expand Up @@ -763,20 +766,25 @@ TEST(DOMLink, ResolveAutoInertialsWithMass)
root.ResolveAutoInertials(errors, sdfParserConfig);
EXPECT_TRUE(errors.empty());

EXPECT_DOUBLE_EQ(4.0, link->Inertial().MassMatrix().Mass());
EXPECT_NE(4.0, link->Inertial().MassMatrix().Mass());
EXPECT_EQ(gz::math::Pose3d::Zero, link->Inertial().Pose());
EXPECT_EQ(gz::math::Vector3d(0.66666, 0.66666, 0.66666),
EXPECT_EQ(gz::math::Vector3d(0.33333, 0.33333, 0.33333),
link->Inertial().MassMatrix().DiagonalMoments());
}

/////////////////////////////////////////////////
TEST(DOMLink, InertialValuesGivenWithAutoSetToTrue)
TEST(DOMLink, ResolveAutoInertialsWithMass)
{
// A model with link inertial auto set to true.
// The inertia matrix is specified but should be ignored.
// <mass> is speicifed - the auto computed inertial values should
// be scaled based on the desired mass.
std::string sdf = "<?xml version=\"1.0\"?>"
"<sdf version=\"1.11\">"
" <model name='compound_model'>"
" <link name='compound_link'>"
" <inertial auto='true'>"
" <mass>4.0</mass>"
" <pose>1 1 1 2 2 2</pose>"
" <inertia>"
" <ixx>1</ixx>"
Expand Down Expand Up @@ -807,12 +815,14 @@ TEST(DOMLink, InertialValuesGivenWithAutoSetToTrue)
root.ResolveAutoInertials(errors, sdfParserConfig);
EXPECT_TRUE(errors.empty());

EXPECT_NE(4.0, link->Inertial().MassMatrix().Mass());
EXPECT_DOUBLE_EQ(4.0, link->Inertial().MassMatrix().Mass());
EXPECT_EQ(gz::math::Pose3d::Zero, link->Inertial().Pose());
EXPECT_EQ(gz::math::Vector3d(0.33333, 0.33333, 0.33333),
EXPECT_EQ(gz::math::Vector3d(0.66666, 0.66666, 0.66666),
link->Inertial().MassMatrix().DiagonalMoments());
}



/////////////////////////////////////////////////
TEST(DOMLink, ResolveAutoInertialsCalledWithAutoFalse)
{
Expand Down

0 comments on commit cf4d77b

Please sign in to comment.