diff --git a/src/Param.cc b/src/Param.cc
index a18f42106..e1968a275 100644
--- a/src/Param.cc
+++ b/src/Param.cc
@@ -301,7 +301,11 @@ std::string Param::GetAsString() const
{
StringStreamClassicLocale ss;
- ss << ParamStreamer{ this->dataPtr->value };
+ if (this->dataPtr->strValue.has_value())
+ ss << this->dataPtr->strValue.value();
+ else
+ ss << ParamStreamer{ this->dataPtr->value };
+
return ss.str();
}
diff --git a/test/integration/include_custom_model_expected_output.sdf b/test/integration/include_custom_model_expected_output.sdf
index df2dd0d2a..d50a2e11e 100644
--- a/test/integration/include_custom_model_expected_output.sdf
+++ b/test/integration/include_custom_model_expected_output.sdf
@@ -24,9 +24,9 @@
- 0.5 0.5 1 1
- 0.5 0.5 1 1
- 0 0 1 1
+ 0.5 0.5 1.0 1
+ 0.5 0.5 1.0 1
+ 0.0 0.0 1.0 1
@@ -72,12 +72,12 @@
0.01
- 1
+ true
1
-->
- -1.06 0 0 0 -0 3.14
+ -1.06 0 0 0 0 3.14
1.047
@@ -92,7 +92,7 @@
+ true -->
30
chassis/camera
@@ -100,7 +100,7 @@
- -1.06 0 0 0 -0 3.14
+ -1.06 0 0 0 0 3.14
0.1 0.1 0.1
@@ -110,7 +110,7 @@
- 0.6 0 0.7 0 -0 0
+ 0.6 0 0.7 0 0 0
@@ -170,7 +170,7 @@
-->
- -0.2 0 0.3 0 -0 3.14
+ -0.2 0 0.3 0 0 3.14
@@ -205,13 +205,13 @@
- 0.1 0.2 0.3 0 -0 0
+ 0.1 0.2 0.3 0 0 0
- 1.047
+ 1.0469999999999999
1280
@@ -232,7 +232,7 @@
20
- 1
+ true
top/cam
@@ -332,7 +332,7 @@
- 0 0 0 0 0 0
+ 0 0 0 0 -0 0
@@ -408,7 +408,7 @@
- 1 1 1 0 -0 0
+ 1 1 1 0 0 0
@@ -429,7 +429,7 @@
- 0 0 0 0 -0 0
+ 0 0 0 0 0 0
1.047
@@ -444,7 +444,7 @@
1
30
- 1
+ true
diff --git a/test/integration/include_custom_nested_model_expected_output.sdf b/test/integration/include_custom_nested_model_expected_output.sdf
index 08eea7116..b8dfc81d7 100644
--- a/test/integration/include_custom_nested_model_expected_output.sdf
+++ b/test/integration/include_custom_nested_model_expected_output.sdf
@@ -11,7 +11,7 @@
0.126164
0
0
- 0.41651899999999997
+ 0.416519
0
0.481014
@@ -23,9 +23,9 @@
- 0.5 0.5 1 1
- 0.5 0.5 1 1
- 0 0 1 1
+ 0.5 0.5 1.0 1
+ 0.5 0.5 1.0 1
+ 0.0 0.0 1.0 1
@@ -73,32 +73,32 @@
0.01
- 1
+ true
1
-->
- -1.06 0 0 0 -0 3.14
+ -1.06 0 0 0 0 3.14
- 1.0469999999999999
+ 1.047
320
240
- 0.10000000000000001
+ 0.1
100
1
30
- 1
+ true
chassis/camera
- -1.06 0 0 0 -0 3.14
+ -1.06 0 0 0 0 3.14
0.1 0.1 0.1
@@ -108,7 +108,7 @@
- 0.6 0 0.7 0 -0 0
+ 0.6 0 0.7 0 0 0
@@ -132,7 +132,7 @@
- -0.2 0 0.3 0 -0 3.14
+ -0.2 0 0.3 0 0 3.14
0.05
@@ -154,17 +154,17 @@
- 0 0 0 0 -0 3.14
+ 0 0 0 0 0 3.14
- 1.0469999999999999
+ 1.047
320
240
- 0.10000000000000001
+ 0.1
100
@@ -172,21 +172,21 @@
60
- 1
+ true
top/camera
- -0.2 0 0.3 0 -0 3.14
+ -0.2 0 0.3 0 0 3.14
- 0.050000000000000003
+ 0.05
- 0 0 0 0 -0 0
+ 0 0 0 0 0 0
top
@@ -199,14 +199,14 @@
- 0 0 0 0 -0 0
+ 0 0 0 0 0 0
2
- 0.14583299999999999
+ 0.145833
0
0
- 0.14583299999999999
+ 0.145833
0
0.125
@@ -214,7 +214,7 @@
- 0.29999999999999999
+ 0.3
@@ -226,7 +226,7 @@
- 0.29999999999999999
+ 0.3
@@ -235,14 +235,14 @@
- 0 0 0 0 -0 0
+ 0 0 0 0 0 0
2
- 0.14583299999999999
+ 0.145833
0
0
- 0.14583299999999999
+ 0.145833
0
0.125
@@ -250,7 +250,7 @@
- 0.29999999999999999
+ 0.3
@@ -262,7 +262,7 @@
- 0.29999999999999999
+ 0.3
@@ -271,14 +271,14 @@
- 0 0 0 0 -0 0
+ 0 0 0 0 0 0
2
- 0.14583299999999999
+ 0.145833
0
0
- 0.14583299999999999
+ 0.145833
0
0.125
@@ -286,7 +286,7 @@
- 0.29999999999999999
+ 0.3
@@ -298,7 +298,7 @@
- 0.29999999999999999
+ 0.3
@@ -311,8 +311,8 @@
0 0 1
- -1.7976900000000001e+308
- 1.7976900000000001e+308
+ -1.79769e+308
+ 1.79769e+308
@@ -322,8 +322,8 @@
0 0 1
- -1.7976900000000001e+308
- 1.7976900000000001e+308
+ -1.79769e+308
+ 1.79769e+308
diff --git a/test/integration/nested_model_with_frames_expected.sdf b/test/integration/nested_model_with_frames_expected.sdf
index 8358e2519..3b4e7a8d3 100644
--- a/test/integration/nested_model_with_frames_expected.sdf
+++ b/test/integration/nested_model_with_frames_expected.sdf
@@ -4,7 +4,7 @@
- 0 0 0 1.5708 -0 0
+ 0 0 0 1.570796 0 0
0 0 0 0 0.785398 0
@@ -29,13 +29,13 @@
- 1 0 0 0 -0 0
+ 1 0 0 0 0 0
- 0 1 0 0 -0 0
+ 0 1 0 0 0 0
- 0 0 1 0 -0 0
+ 0 0 1 0 0 0
0 0 0 0 -0 0
@@ -49,7 +49,7 @@
- 0 0 1 0 -0 0
+ 0 0 1 0 0 0
L2
L3
@@ -57,14 +57,14 @@
- 1 0 1 0 -0 0
+ 1 0 1 0 0 0
L3
L4
- 1 0 0 0 -0 0
+ 1 0 0 0 0 0
- 1 0 0 0 -0 0
+ 1 0 0 0 0 0
10 0 0 0 -0 1.5708
diff --git a/test/integration/pose_1_9_sdf.cc b/test/integration/pose_1_9_sdf.cc
index 4667c67dc..b315bb62c 100644
--- a/test/integration/pose_1_9_sdf.cc
+++ b/test/integration/pose_1_9_sdf.cc
@@ -402,3 +402,98 @@ TEST(Pose1_9, ChangingAttributeOfParentElement)
ASSERT_TRUE(valParam->Get(val));
EXPECT_EQ(Pose(1, 2, 3, 0.4, 0.5, 0.6), val);
}
+
+//////////////////////////////////////////////////
+TEST(Pose1_9, ToStringWithoutAttrib)
+{
+ sdf::ElementPtr poseElem(new sdf::Element);
+ poseElem->SetName("pose");
+ poseElem->AddValue("pose", "0 0 0 0 0 0", true);
+ poseElem->AddAttribute("relative_to", "string", "", false);
+ poseElem->AddAttribute("degrees", "bool", "false", false);
+
+ sdf::ParamPtr poseValueParam = poseElem->GetValue();
+ ASSERT_NE(nullptr, poseValueParam);
+ EXPECT_TRUE(poseValueParam->SetFromString("1 2 3 0.4 0.5 0.6"));
+
+ std::string elemStr = poseElem->ToString("");
+ EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6");
+}
+
+//////////////////////////////////////////////////
+TEST(Pose1_9, ToStringWithDegreesFalse)
+{
+ sdf::ElementPtr poseElem(new sdf::Element);
+ poseElem->SetName("pose");
+ poseElem->AddValue("pose", "0 0 0 0 0 0", true);
+ poseElem->AddAttribute("relative_to", "string", "", false);
+ poseElem->AddAttribute("degrees", "bool", "false", false);
+
+ sdf::ParamPtr degreesAttrib = poseElem->GetAttribute("degrees");
+ ASSERT_NE(nullptr, degreesAttrib);
+ ASSERT_TRUE(degreesAttrib->Set(false));
+
+ sdf::ParamPtr poseValueParam = poseElem->GetValue();
+ ASSERT_NE(nullptr, poseValueParam);
+ EXPECT_TRUE(poseValueParam->SetFromString("1 2 3 0.4 0.5 0.6"));
+
+ std::string elemStr = poseElem->ToString("");
+ EXPECT_PRED2(contains, elemStr, "degrees='0'");
+ EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6");
+}
+
+//////////////////////////////////////////////////
+TEST(Pose1_9, ToStringWithDegreesTrue)
+{
+ sdf::ElementPtr poseElem(new sdf::Element);
+ poseElem->SetName("pose");
+ poseElem->AddValue("pose", "0 0 0 0 0 0", true);
+ poseElem->AddAttribute("relative_to", "string", "", false);
+ poseElem->AddAttribute("degrees", "bool", "false", false);
+
+ sdf::ParamPtr degreesAttrib = poseElem->GetAttribute("degrees");
+ ASSERT_NE(nullptr, degreesAttrib);
+ ASSERT_TRUE(degreesAttrib->Set(true));
+
+ sdf::ParamPtr poseValueParam = poseElem->GetValue();
+ ASSERT_NE(nullptr, poseValueParam);
+ EXPECT_TRUE(poseValueParam->SetFromString("1 2 3 0.4 0.5 0.6"));
+
+ std::string elemStr = poseElem->ToString("");
+ EXPECT_PRED2(contains, elemStr, "degrees='1'");
+ EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6");
+}
+
+//////////////////////////////////////////////////
+TEST(Pose1_9, ToStringAfterChangingDegreeAttribute)
+{
+ using Pose = ignition::math::Pose3d;
+
+ sdf::ElementPtr poseElem(new sdf::Element);
+ poseElem->SetName("pose");
+ poseElem->AddValue("pose", "0 0 0 0 0 0", true);
+ poseElem->AddAttribute("relative_to", "string", "", false);
+ poseElem->AddAttribute("degrees", "bool", "false", false);
+
+ // Param value in radians
+ sdf::ParamPtr valParam = poseElem->GetValue();
+ ASSERT_NE(nullptr, valParam);
+ ASSERT_TRUE(valParam->SetFromString("1 2 3 0.4 0.5 0.6"));
+
+ std::string elemStr = poseElem->ToString("");
+ EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6");
+
+ // Changing to degrees
+ sdf::ParamPtr degreesAttrib = poseElem->GetAttribute("degrees");
+ ASSERT_NE(nullptr, degreesAttrib);
+ ASSERT_TRUE(degreesAttrib->Set(true));
+ elemStr = poseElem->ToString("");
+ EXPECT_PRED2(contains, elemStr, "degrees='1'");
+ EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6");
+
+ // Changing back to radians
+ ASSERT_TRUE(degreesAttrib->Set(false));
+ elemStr = poseElem->ToString("");
+ EXPECT_PRED2(contains, elemStr, "degrees='0'");
+ EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6");
+}
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 a73e206d2..d907410ac 100644
--- a/test/integration/two_level_nested_model_with_frames_expected.sdf
+++ b/test/integration/two_level_nested_model_with_frames_expected.sdf
@@ -5,7 +5,7 @@
- 0 0 0 1.5708 -0 0
+ 0 0 0 1.570796 0 0
0 0 0 0 0.785398 0
@@ -30,13 +30,13 @@
- 1 0 0 0 -0 0
+ 1 0 0 0 0 0
- 0 1 0 0 -0 0
+ 0 1 0 0 0 0
- 0 0 1 0 -0 0
+ 0 0 1 0 0 0
0 0 0 0 -0 0
@@ -50,7 +50,7 @@
- 0 0 1 0 -0 0
+ 0 0 1 0 0 0
L2
L3
@@ -58,17 +58,17 @@
- 1 0 1 0 -0 0
+ 1 0 1 0 0 0
L3
L4
- 1 0 0 0 -0 0
+ 1 0 0 0 0 0
- 1 0 0 0 -0 0
+ 1 0 0 0 0 0
- 0 10 0 1.5708 -0 0
+ 0 10 0 1.570796326794895 0 0
10 0 0 0 -0 1.5708