Skip to content

Commit

Permalink
translation only for direct comparison tests
Browse files Browse the repository at this point in the history
Signed-off-by: Jenn Nguyen <[email protected]>
  • Loading branch information
jennuine committed Apr 5, 2022
1 parent 499f65a commit e1f6421
Show file tree
Hide file tree
Showing 6 changed files with 88 additions and 17 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<?xml version="1.0"?>

<model>
<name>test_model_with_frames</name>
<sdf version="1.7">model.sdf</sdf>
</model>
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
<?xml version="1.0" ?>
<sdf version="1.7">
<model name="test_model_with_frames">
<frame name="F1">
<pose>0.12345 0 0 0 0 0</pose>
</frame>
<frame name="F2">
<pose relative_to="F1">0 1.2345 0 0 0 0</pose>
</frame>
<link name="L1">
<pose relative_to="F1"/>
<visual name="V1">
<pose relative_to="F2"/>
<geometry>
<sphere>
<radius>1.5707963267948966</radius>
</sphere>
</geometry>
</visual>
<collision name="C1">
<pose relative_to="__model__"/>
<geometry>
<sphere>
<radius>0.78539816339744828</radius>
</sphere>
</geometry>
</collision>
</link>
<link name="L2">
<pose relative_to="F1">1 0 0 0 0 0</pose>
</link>
<link name="L3">
<pose relative_to="L2">0 1 0 0 0 0</pose>
</link>
<link name="L4">
<pose relative_to="__model__">0 0 1 0 0 0</pose>
</link>
<joint name="J1" type="universal">
<pose relative_to="L1"/>
<parent>L1</parent>
<child>L2</child>
<axis>
<xyz expressed_in="F2">0 0 1</xyz>
</axis>
<axis2>
<xyz expressed_in="F2">1 0 0</xyz>
</axis2>
</joint>
<joint name="J2" type="revolute">
<pose relative_to="">0 0 1 0 0 0</pose>
<parent>L2</parent>
<child>L3</child>
<axis>
<xyz expressed_in="__model__">0 0 1</xyz>
</axis>
</joint>
<joint name="J3" type="fixed">
<pose relative_to="__model__">1 0 1 0 0 0</pose>
<parent>L3</parent>
<child>L4</child>
</joint>
<model name="M2">
<pose relative_to="F1">1 0 0 0 0 0</pose>
<link name="L5">
<pose>1 0 0 0 0 0</pose>
</link>
</model>
</model>
</sdf>
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
<model name="test_nested_model_with_frames">
<include>
<!-- This search path for this model must be added by the test code -->
<uri>test_model_with_frames</uri>
<pose>0 10 0 1.570796326794895 0 0</pose>
<uri>test_model_with_frames_no_rotations</uri>
<pose>0 10 0 0 0 0</pose>
</include>
</model>
</sdf>
12 changes: 4 additions & 8 deletions test/integration/nested_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -574,15 +574,15 @@ void prepareForDirectComparison(sdf::ElementPtr _worldElem)
}

//////////////////////////////////////////////////
// Test parsing models with child models containg frames nested via <include>
// Test parsing models with child models containing frames nested via <include>
// Compare parsed SDF with expected string
TEST(NestedModel, NestedModelWithFramesDirectComparison)
{
const std::string name = "test_model_with_frames";
const std::string name = "test_model_with_frames_no_rotations";
const std::string modelPath =
sdf::testing::TestFile("integration", "model", name);

const ignition::math::Pose3d model1Pose(10, 0, 0, 0, 0, IGN_PI/2);
const ignition::math::Pose3d model1Pose(10, 0, 0, 0, 0, 0);

std::ostringstream stream;
std::string version = "1.7";
Expand All @@ -609,8 +609,6 @@ TEST(NestedModel, NestedModelWithFramesDirectComparison)
prepareForDirectComparison(worldElem);

// Compare with expected output
// There is a small loss of precision (~2e-16) in poses, which is related to:
// https://github.com/ignitionrobotics/ign-math/issues/212
const std::string expectedSdfPath =
sdf::testing::TestFile(
"integration", "nested_model_with_frames_expected.sdf");
Expand Down Expand Up @@ -733,7 +731,7 @@ TEST(NestedModel, TwoLevelNestedModelWithFramesDirectComparison)
const std::string modelPath = sdf::testing::TestFile(
"integration", "model", name);

const ignition::math::Pose3d model1Pose(10, 0, 0, 0, 0, IGN_PI/2);
const ignition::math::Pose3d model1Pose(10, 0, 0, 0, 0, 0);

std::ostringstream stream;
std::string version = "1.7";
Expand Down Expand Up @@ -767,8 +765,6 @@ TEST(NestedModel, TwoLevelNestedModelWithFramesDirectComparison)
prepareForDirectComparison(worldElem);

// Compare with expected output
// There is a small loss of precision (~2e-16) in poses, which is related to:
// https://github.com/ignitionrobotics/ign-math/issues/212
const std::string expectedSdfPath =
sdf::testing::TestFile(
"integration", "two_level_nested_model_with_frames_expected.sdf");
Expand Down
6 changes: 3 additions & 3 deletions test/integration/nested_model_with_frames_expected.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
<model name='ParentModel'>
<model name='M1'>
<frame name='F1'>
<pose>0 0 0 1.5707959999999999 0 0</pose>
<pose>0.12345 0 0 0 0 0</pose>
</frame>
<frame name='F2'>
<pose relative_to='F1'>0 0 0 0 0.78539799999999993 0</pose>
<pose relative_to='F1'>0 1.2344999999999999 0 0 0 0</pose>
</frame>
<link name='L1'>
<pose relative_to='F1'>0 0 0 0 0 0</pose>
Expand Down Expand Up @@ -67,7 +67,7 @@
<pose>1 0 0 0 0 0</pose>
</link>
</model>
<pose>10 0 0 0 0 1.5708</pose>
<pose>10 0 0 0 0 0</pose>
</model>
</model>
</world>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@
<model name='M1'>
<model name='test_model_with_frames'>
<frame name='F1'>
<pose>0 0 0 1.5707959999999999 0 0</pose>
<pose>0.12345 0 0 0 0 0</pose>
</frame>
<frame name='F2'>
<pose relative_to='F1'>0 0 0 0 0.78539799999999993 0</pose>
<pose relative_to='F1'>0 1.2344999999999999 0 0 0 0</pose>
</frame>
<link name='L1'>
<pose relative_to='F1'>0 0 0 0 0 0</pose>
Expand Down Expand Up @@ -68,9 +68,9 @@
<pose>1 0 0 0 0 0</pose>
</link>
</model>
<pose>0 10 0 1.5707963267948948 0 0</pose>
<pose>0 10 0 0 0 0</pose>
</model>
<pose>10 0 0 0 0 1.5708</pose>
<pose>10 0 0 0 0 0</pose>
</model>
</model>
</world>
Expand Down

0 comments on commit e1f6421

Please sign in to comment.