diff --git a/test/integration/model/test_model_with_frames_no_rotations/model.config b/test/integration/model/test_model_with_frames_no_rotations/model.config
new file mode 100644
index 000000000..33e622b95
--- /dev/null
+++ b/test/integration/model/test_model_with_frames_no_rotations/model.config
@@ -0,0 +1,6 @@
+
+
+
+ test_model_with_frames
+ model.sdf
+
diff --git a/test/integration/model/test_model_with_frames_no_rotations/model.sdf b/test/integration/model/test_model_with_frames_no_rotations/model.sdf
new file mode 100644
index 000000000..769175115
--- /dev/null
+++ b/test/integration/model/test_model_with_frames_no_rotations/model.sdf
@@ -0,0 +1,69 @@
+
+
+
+
+ 0.12345 0 0 0 0 0
+
+
+ 0 1.2345 0 0 0 0
+
+
+
+
+
+
+
+ 1.5707963267948966
+
+
+
+
+
+
+
+ 0.78539816339744828
+
+
+
+
+
+ 1 0 0 0 0 0
+
+
+ 0 1 0 0 0 0
+
+
+ 0 0 1 0 0 0
+
+
+
+ L1
+ L2
+
+ 0 0 1
+
+
+ 1 0 0
+
+
+
+ 0 0 1 0 0 0
+ L2
+ L3
+
+ 0 0 1
+
+
+
+ 1 0 1 0 0 0
+ L3
+ L4
+
+
+ 1 0 0 0 0 0
+
+ 1 0 0 0 0 0
+
+
+
+
diff --git a/test/integration/model/test_nested_model_with_frames/model.sdf b/test/integration/model/test_nested_model_with_frames/model.sdf
index b28a42b4f..7716ebeea 100644
--- a/test/integration/model/test_nested_model_with_frames/model.sdf
+++ b/test/integration/model/test_nested_model_with_frames/model.sdf
@@ -3,8 +3,8 @@
- test_model_with_frames
- 0 10 0 1.570796326794895 0 0
+ test_model_with_frames_no_rotations
+ 0 10 0 0 0 0
diff --git a/test/integration/nested_model.cc b/test/integration/nested_model.cc
index bd01621f6..935345fc4 100644
--- a/test/integration/nested_model.cc
+++ b/test/integration/nested_model.cc
@@ -574,15 +574,15 @@ void prepareForDirectComparison(sdf::ElementPtr _worldElem)
}
//////////////////////////////////////////////////
-// Test parsing models with child models containg frames nested via
+// Test parsing models with child models containing frames nested via
// 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";
@@ -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");
@@ -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";
@@ -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");
diff --git a/test/integration/nested_model_with_frames_expected.sdf b/test/integration/nested_model_with_frames_expected.sdf
index ab4f780ac..078f6f7db 100644
--- a/test/integration/nested_model_with_frames_expected.sdf
+++ b/test/integration/nested_model_with_frames_expected.sdf
@@ -4,10 +4,10 @@
- 0 0 0 1.5707959999999999 0 0
+ 0.12345 0 0 0 0 0
- 0 0 0 0 0.78539799999999993 0
+ 0 1.2344999999999999 0 0 0 0
0 0 0 0 0 0
@@ -67,7 +67,7 @@
1 0 0 0 0 0
- 10 0 0 0 0 1.5708
+ 10 0 0 0 0 0
diff --git a/test/integration/two_level_nested_model_with_frames_expected.sdf b/test/integration/two_level_nested_model_with_frames_expected.sdf
index 6728f2478..a0b97a805 100644
--- a/test/integration/two_level_nested_model_with_frames_expected.sdf
+++ b/test/integration/two_level_nested_model_with_frames_expected.sdf
@@ -5,10 +5,10 @@
- 0 0 0 1.5707959999999999 0 0
+ 0.12345 0 0 0 0 0
- 0 0 0 0 0.78539799999999993 0
+ 0 1.2344999999999999 0 0 0 0
0 0 0 0 0 0
@@ -68,9 +68,9 @@
1 0 0 0 0 0
- 0 10 0 1.5707963267948948 0 0
+ 0 10 0 0 0 0
- 10 0 0 0 0 1.5708
+ 10 0 0 0 0 0