@@ -170,7 +170,7 @@ static inline bool _initFile(const std::string &_filename,
170170 return false ;
171171 }
172172
173- return initDoc (&xmlDoc, _config, _sdf, _errors );
173+ return initDoc (_sdf, _errors, &xmlDoc, _config );
174174}
175175
176176// ////////////////////////////////////////////////
@@ -416,7 +416,7 @@ bool init(SDFPtr _sdf, sdf::Errors &_errors, const ParserConfig &_config)
416416 std::string xmldata = SDF::EmbeddedSpec (" root.sdf" , false );
417417 auto xmlDoc = makeSdfDoc ();
418418 xmlDoc.Parse (xmldata.c_str ());
419- return initDoc (&xmlDoc, _config, _sdf, _errors );
419+ return initDoc (_sdf, _errors, &xmlDoc, _config );
420420}
421421
422422// ////////////////////////////////////////////////
@@ -444,7 +444,7 @@ bool initFile(const std::string &_filename, const ParserConfig &_config,
444444 {
445445 auto xmlDoc = makeSdfDoc ();
446446 xmlDoc.Parse (xmldata.c_str ());
447- return initDoc (&xmlDoc, _config, _sdf, _errors );
447+ return initDoc (_sdf, _errors, &xmlDoc, _config );
448448 }
449449 return _initFile (sdf::findFile (_filename, true , false , _config), _config,
450450 _sdf, _errors);
@@ -475,7 +475,7 @@ bool initFile(const std::string &_filename, const ParserConfig &_config,
475475 {
476476 auto xmlDoc = makeSdfDoc ();
477477 xmlDoc.Parse (xmldata.c_str ());
478- return initDoc (&xmlDoc, _config, _sdf, _errors );
478+ return initDoc (_sdf, _errors, &xmlDoc, _config );
479479 }
480480 return _initFile (sdf::findFile (_filename, true , false , _config), _config,
481481 _sdf, _errors);
@@ -503,7 +503,7 @@ bool initString(const std::string &_xmlString, const ParserConfig &_config,
503503 return false ;
504504 }
505505
506- return initDoc (&xmlDoc, _config, _sdf, _errors );
506+ return initDoc (_sdf, _errors, &xmlDoc, _config );
507507}
508508
509509// ////////////////////////////////////////////////
@@ -538,40 +538,40 @@ inline tinyxml2::XMLElement *_initDocGetElement(tinyxml2::XMLDocument *_xmlDoc,
538538}
539539
540540// ////////////////////////////////////////////////
541- bool initDoc (tinyxml2::XMLDocument *_xmlDoc ,
542- const ParserConfig &_config ,
543- SDFPtr _sdf ,
544- sdf::Errors &_errors )
541+ bool initDoc (SDFPtr _sdf ,
542+ sdf::Errors &_errors ,
543+ tinyxml2::XMLDocument *_xmlDoc ,
544+ const ParserConfig &_config )
545545{
546546 auto element = _initDocGetElement (_xmlDoc, _errors);
547547 if (!element)
548548 {
549549 return false ;
550550 }
551551
552- return initXml (element, _config, _sdf->Root (), _errors);
552+ return initXml (_sdf->Root (), _errors, element, _config );
553553}
554554
555555// ////////////////////////////////////////////////
556- bool initDoc (tinyxml2::XMLDocument *_xmlDoc ,
557- const ParserConfig &_config ,
558- ElementPtr _sdf ,
559- sdf::Errors &_errors )
556+ bool initDoc (ElementPtr _sdf ,
557+ sdf::Errors &_errors ,
558+ tinyxml2::XMLDocument *_xmlDoc ,
559+ const ParserConfig &_config )
560560{
561561 auto element = _initDocGetElement (_xmlDoc, _errors);
562562 if (!element)
563563 {
564564 return false ;
565565 }
566566
567- return initXml (element, _config, _sdf, _errors );
567+ return initXml (_sdf, _errors, element, _config );
568568}
569569
570570// ////////////////////////////////////////////////
571- bool initXml (tinyxml2::XMLElement *_xml ,
572- const ParserConfig &_config ,
573- ElementPtr _sdf ,
574- sdf::Errors &_errors )
571+ bool initXml (ElementPtr _sdf ,
572+ sdf::Errors &_errors ,
573+ tinyxml2::XMLElement *_xml ,
574+ const ParserConfig &_config )
575575{
576576 const char *refString = _xml->Attribute (" ref" );
577577 if (refString)
@@ -696,7 +696,7 @@ bool initXml(tinyxml2::XMLElement *_xml,
696696 else
697697 {
698698 ElementPtr element (new Element);
699- initXml (child, _config, element, _errors );
699+ initXml (element, _errors, child, _config );
700700 _sdf->AddElementDescription (element);
701701 }
702702 }
@@ -1254,9 +1254,9 @@ bool checkXmlFromRoot(tinyxml2::XMLElement *_xmlRoot,
12541254}
12551255
12561256// ////////////////////////////////////////////////
1257- std::string getBestSupportedModelVersion (tinyxml2::XMLElement *_modelXML ,
1258- std::string &_modelFileName ,
1259- sdf::Errors &_errors )
1257+ std::string getBestSupportedModelVersion (std::string &_modelFileName ,
1258+ sdf::Errors &_errors ,
1259+ tinyxml2::XMLElement *_modelXML )
12601260{
12611261 tinyxml2::XMLElement *sdfXML = _modelXML->FirstChildElement (" sdf" );
12621262 tinyxml2::XMLElement *nameSearch = _modelXML->FirstChildElement (" name" );
@@ -1380,7 +1380,7 @@ std::string getModelFilePath(sdf::Errors &_errors,
13801380 }
13811381
13821382 std::string modelFileName;
1383- if (getBestSupportedModelVersion (modelXML, modelFileName, _errors).empty ())
1383+ if (getBestSupportedModelVersion (modelFileName, _errors, modelXML ).empty ())
13841384 {
13851385 return std::string ();
13861386 }
0 commit comments