Skip to content

Commit

Permalink
update python test
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 committed Dec 9, 2024
1 parent f253f0d commit d0fdc9c
Showing 1 changed file with 42 additions and 1 deletion.
43 changes: 42 additions & 1 deletion python/test/pyLink_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -482,7 +482,7 @@ def test_resolveauto_inertialsWithMultipleCollisions(self):
self.assertEqual(Vector3d(2.013513, 2.013513, 0.72603),
link.inertial().mass_matrix().diagonal_moments())

def test_inertial_values_given_with_auto_set_to_true(self):
def test_resolveauto_inertialsWithMass(self):
sdf = "<?xml version=\"1.0\"?>" + \
"<sdf version=\"1.11\">" + \
" <model name='compound_model'>" + \
Expand Down Expand Up @@ -519,6 +519,47 @@ def test_inertial_values_given_with_auto_set_to_true(self):
root.resolve_auto_inertials(errors, sdfParserConfig)
self.assertEqual(len(errors), 0)

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

def test_inertial_values_given_with_auto_set_to_true(self):
sdf = "<?xml version=\"1.0\"?>" + \
"<sdf version=\"1.11\">" + \
" <model name='compound_model'>" + \
" <link name='compound_link'>" + \
" <inertial auto='True'>" + \
" <pose>1 1 1 2 2 2</pose>" + \
" <inertia>" + \
" <ixx>1</ixx>" + \
" <iyy>1</iyy>" + \
" <izz>1</izz>" + \
" </inertia>" + \
" </inertial>" + \
" <collision name='box_collision'>" + \
" <density>2.0</density>" + \
" <geometry>" + \
" <box>" + \
" <size>1 1 1</size>" + \
" </box>" + \
" </geometry>" + \
" </collision>" + \
" </link>" + \
" </model>" + \
" </sdf>"

root = Root()
sdfParserConfig = ParserConfig()
errors = root.load_sdf_string(sdf, sdfParserConfig)
self.assertEqual(errors, None)

model = root.model()
link = model.link_by_index(0)
errors = []
root.resolve_auto_inertials(errors, sdfParserConfig)
self.assertEqual(len(errors), 0)

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

0 comments on commit d0fdc9c

Please sign in to comment.