@@ -33,20 +33,24 @@ std::string getMinimalUrdfTxt()
3333}
3434
3535// ///////////////////////////////////////////////
36- std::string convertUrdfStrToSdfStr (const std::string &_urdf)
36+ std::string convertUrdfStrToSdfStr (
37+ const std::string &_urdf,
38+ const sdf::ParserConfig &_config = sdf::ParserConfig::GlobalConfig())
3739{
3840 sdf::URDF2SDF parser_;
3941 tinyxml2::XMLDocument sdf_result;
40- parser_.InitModelString (_urdf, &sdf_result);
42+ parser_.InitModelString (_urdf, _config, &sdf_result);
4143 tinyxml2::XMLPrinter printer;
4244 sdf_result.Accept (&printer);
4345 return printer.CStr ();
4446}
4547
4648// ///////////////////////////////////////////////
47- void convertUrdfStrToSdf (const std::string &_urdf, sdf::SDF &_sdf)
49+ void convertUrdfStrToSdf (
50+ const std::string &_urdf, sdf::SDF &_sdf,
51+ const sdf::ParserConfig &_config = sdf::ParserConfig::GlobalConfig())
4852{
49- _sdf.SetFromString (convertUrdfStrToSdfStr (_urdf));
53+ _sdf.SetFromString (convertUrdfStrToSdfStr (_urdf, _config ));
5054}
5155
5256// ///////////////////////////////////////////////
@@ -57,8 +61,9 @@ TEST(URDFParser, InitModelDoc_EmptyDoc_NoThrow)
5761 ASSERT_NO_THROW (
5862 tinyxml2::XMLDocument doc = tinyxml2::XMLDocument ();
5963 sdf::URDF2SDF parser_;
64+ sdf::ParserConfig config_;
6065 tinyxml2::XMLDocument sdf_result;
61- parser_.InitModelDoc (&doc, &sdf_result);
66+ parser_.InitModelDoc (&doc, config_, &sdf_result);
6267 ); // NOLINT(whitespace/parens)
6368}
6469
@@ -70,8 +75,9 @@ TEST(URDFParser, InitModelDoc_BasicModel_NoThrow)
7075 tinyxml2::XMLDocument doc;
7176 doc.Parse (getMinimalUrdfTxt ().c_str ());
7277 sdf::URDF2SDF parser_;
78+ sdf::ParserConfig config_;
7379 tinyxml2::XMLDocument sdf_result;
74- parser_.InitModelDoc (&doc, &sdf_result);
80+ parser_.InitModelDoc (&doc, config_, &sdf_result);
7581 ); // NOLINT(whitespace/parens)
7682}
7783
@@ -82,9 +88,10 @@ TEST(URDFParser, ParseResults_BasicModel_ParseEqualToModel)
8288 tinyxml2::XMLDocument doc;
8389 doc.Parse (getMinimalUrdfTxt ().c_str ());
8490 sdf::URDF2SDF parser_;
91+ sdf::ParserConfig config_;
8592
8693 tinyxml2::XMLDocument sdf_result;
87- parser_.InitModelDoc (&doc, &sdf_result);
94+ parser_.InitModelDoc (&doc, config_, &sdf_result);
8895
8996 tinyxml2::XMLPrinter printer;
9097 sdf_result.Print (&printer);
@@ -117,8 +124,9 @@ TEST(URDFParser, ParseRobotOriginXYZBlank)
117124 tinyxml2::XMLDocument doc;
118125 doc.Parse (stream.str ().c_str ());
119126 sdf::URDF2SDF parser_;
127+ sdf::ParserConfig config_;
120128 tinyxml2::XMLDocument sdf_result;
121- parser_.InitModelDoc (&doc, &sdf_result);
129+ parser_.InitModelDoc (&doc, config_, &sdf_result);
122130 tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement (" sdf" );
123131 ASSERT_NE (nullptr , sdf);
124132 tinyxml2::XMLElement *model = sdf->FirstChildElement (" model" );
@@ -138,8 +146,9 @@ TEST(URDFParser, ParseRobotOriginRPYBlank)
138146 tinyxml2::XMLDocument doc;
139147 sdf::URDF2SDF parser_;
140148 doc.Parse (stream.str ().c_str ());
149+ sdf::ParserConfig config_;
141150 tinyxml2::XMLDocument sdf_result;
142- parser_.InitModelDoc (&doc, &sdf_result);
151+ parser_.InitModelDoc (&doc, config_, &sdf_result);
143152 tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement (" sdf" );
144153 ASSERT_NE (nullptr , sdf);
145154 tinyxml2::XMLElement *model = sdf->FirstChildElement (" model" );
@@ -172,8 +181,9 @@ TEST(URDFParser, ParseRobotMaterialBlank)
172181 tinyxml2::XMLDocument doc;
173182 doc.Parse (stream.str ().c_str ());
174183 sdf::URDF2SDF parser;
184+ sdf::ParserConfig config_;
175185 tinyxml2::XMLDocument sdfXml;
176- parser.InitModelDoc (&doc, &sdfXml);
186+ parser.InitModelDoc (&doc, config_, &sdfXml);
177187 auto sdfElem = sdfXml.FirstChildElement (" sdf" );
178188 ASSERT_NE (nullptr , sdfElem);
179189 auto modelElem = sdfElem->FirstChildElement (" model" );
@@ -214,9 +224,10 @@ TEST(URDFParser, ParseRobotMaterialName)
214224 tinyxml2::XMLDocument doc;
215225 doc.Parse (stream.str ().c_str ());
216226 sdf::URDF2SDF parser;
227+ sdf::ParserConfig config_;
217228
218229 tinyxml2::XMLDocument sdfXml;
219- parser.InitModelDoc (&doc, &sdfXml);
230+ parser.InitModelDoc (&doc, config_, &sdfXml);
220231
221232 auto sdfElem = sdfXml.FirstChildElement (" sdf" );
222233 ASSERT_NE (nullptr , sdfElem);
@@ -254,8 +265,9 @@ TEST(URDFParser, ParseRobotOriginInvalidXYZ)
254265 tinyxml2::XMLDocument doc;
255266 sdf::URDF2SDF parser_;
256267 doc.Parse (stream.str ().c_str ());
268+ sdf::ParserConfig config_;
257269 tinyxml2::XMLDocument sdf_result;
258- parser_.InitModelDoc (&doc, &sdf_result);
270+ parser_.InitModelDoc (&doc, config_, &sdf_result);
259271 tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement (" sdf" );
260272 ASSERT_NE (nullptr , sdf);
261273 tinyxml2::XMLElement *model = sdf->FirstChildElement (" model" );
@@ -316,8 +328,9 @@ TEST(URDFParser, ParseGazeboLinkFactors)
316328 tinyxml2::XMLDocument doc;
317329 sdf::URDF2SDF parser_;
318330 doc.Parse (stream.str ().c_str ());
331+ sdf::ParserConfig config_;
319332 tinyxml2::XMLDocument sdf_result;
320- parser_.InitModelDoc (&doc, &sdf_result);
333+ parser_.InitModelDoc (&doc, config_, &sdf_result);
321334
322335 tinyxml2::XMLElement *tmp = sdf_result.FirstChildElement (" sdf" );
323336 ASSERT_NE (nullptr , tmp);
@@ -355,8 +368,9 @@ TEST(URDFParser, ParseGazeboInvalidDampingFactor)
355368 tinyxml2::XMLDocument doc;
356369 sdf::URDF2SDF parser_;
357370 doc.Parse (stream.str ().c_str ());
371+ sdf::ParserConfig config_;
358372 tinyxml2::XMLDocument sdf_result;
359- ASSERT_THROW (parser_.InitModelDoc (&doc, &sdf_result),
373+ ASSERT_THROW (parser_.InitModelDoc (&doc, config_, &sdf_result),
360374 std::invalid_argument);
361375
362376 parser_.ListSDFExtensions ();
@@ -428,8 +442,9 @@ TEST(URDFParser, ParseGazeboJointElements)
428442 tinyxml2::XMLDocument doc;
429443 sdf::URDF2SDF parser_;
430444 doc.Parse (stream.str ().c_str ());
445+ sdf::ParserConfig config_;
431446 tinyxml2::XMLDocument sdf_result;
432- parser_.InitModelDoc (&doc, &sdf_result);
447+ parser_.InitModelDoc (&doc, config_, &sdf_result);
433448
434449 tinyxml2::XMLElement *tmp = sdf_result.FirstChildElement (" sdf" );
435450 ASSERT_NE (nullptr , tmp);
@@ -583,6 +598,55 @@ TEST(URDFParser, CheckFixedJointOptions_preserveFixedJoint)
583598 ASSERT_EQ (jointType, " fixed" );
584599}
585600
601+ // ///////////////////////////////////////////////
602+ TEST (URDFParser, CheckParserConfig_preserveFixedJoint)
603+ {
604+ // Convert a fixed joint with only preserveFixedJoint
605+ // (i.e. converted to fixed joint)
606+ std::ostringstream fixedJointPreserveFixedJoint;
607+ fixedJointPreserveFixedJoint << " <robot name='test_robot'>"
608+ << " <link name='link1'>"
609+ << " <inertial>"
610+ << " <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>"
611+ << " <mass value='1.0'/>"
612+ << " <inertia ixx='1.0' ixy='0.0' ixz='0.0'"
613+ << " iyy='1.0' iyz='0.0' izz='1.0'/>"
614+ << " </inertial>"
615+ << " </link>"
616+ << " <link name='link2'>"
617+ << " <inertial>"
618+ << " <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>"
619+ << " <mass value='1.0'/>"
620+ << " <inertia ixx='1.0' ixy='0.0' ixz='0.0'"
621+ << " iyy='1.0' iyz='0.0' izz='1.0'/>"
622+ << " </inertial>"
623+ << " </link>"
624+ << " <joint name='joint1_2' type='fixed'>"
625+ << " <parent link='link1' />"
626+ << " <child link='link2' />"
627+ << " <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0' />"
628+ << " </joint>"
629+ << " </robot>" ;
630+
631+ // Check that there is a fixed joint in the converted SDF
632+ sdf::SDF fixedJointPreserveFixedJointSDF;
633+
634+ // Set the config option to preserve fixed joints.
635+ sdf::ParserConfig config;
636+ config.URDFSetPreserveFixedJoint (true );
637+
638+ convertUrdfStrToSdf (fixedJointPreserveFixedJoint.str (),
639+ fixedJointPreserveFixedJointSDF, config);
640+ sdf::ElementPtr elem = fixedJointPreserveFixedJointSDF.Root ();
641+ ASSERT_NE (nullptr , elem);
642+ ASSERT_TRUE (elem->HasElement (" model" ));
643+ elem = elem->GetElement (" model" );
644+ ASSERT_TRUE (elem->HasElement (" joint" ));
645+ elem = elem->GetElement (" joint" );
646+ std::string jointType = elem->Get <std::string>(" type" );
647+ ASSERT_EQ (jointType, " fixed" );
648+ }
649+
586650// ///////////////////////////////////////////////
587651TEST (URDFParser,
588652 CheckFixedJointOptions_preserveFixedJoint_and_disableJointLumping)
@@ -817,8 +881,9 @@ TEST(URDFParser, OutputPrecision)
817881 </robot>)" ;
818882
819883 sdf::URDF2SDF parser;
884+ sdf::ParserConfig config_;
820885 tinyxml2::XMLDocument sdfResult;
821- parser.InitModelString (str, &sdfResult);
886+ parser.InitModelString (str, config_, &sdfResult);
822887
823888 auto root = sdfResult.RootElement ();
824889 auto model = root->FirstChildElement (" model" );
@@ -891,8 +956,9 @@ TEST(URDFParser, ParseWhitespace)
891956 doc.Parse (str.c_str ());
892957
893958 sdf::URDF2SDF parser;
959+ sdf::ParserConfig config_;
894960 tinyxml2::XMLDocument sdfXml;
895- parser.InitModelDoc (&doc, &sdfXml);
961+ parser.InitModelDoc (&doc, config_, &sdfXml);
896962
897963 auto root = sdfXml.RootElement ();
898964 ASSERT_NE (nullptr , root);
0 commit comments