diff --git a/.github/workflows/linux-ubuntu-bionic.yml b/.github/workflows/linux-ubuntu-bionic.yml index 236f50289..50a6f883e 100644 --- a/.github/workflows/linux-ubuntu-bionic.yml +++ b/.github/workflows/linux-ubuntu-bionic.yml @@ -16,7 +16,7 @@ jobs: sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" > /etc/apt/sources.list.d/gazebo-stable.list'; sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys D2486D2DD83DB69272AFE98867170598AF249743; sudo apt-get update; - sudo apt -y install cmake build-essential curl g++-8 git mercurial libtinyxml-dev libxml2-utils ruby-dev python-psutil cppcheck; + sudo apt -y install cmake build-essential curl g++-8 git mercurial libtinyxml2-dev libxml2-utils ruby-dev python-psutil cppcheck; sudo update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-8 800 --slave /usr/bin/g++ g++ /usr/bin/g++-8 --slave /usr/bin/gcov gcov /usr/bin/gcov-8; # workaround for https://github.com/rubygems/rubygems/issues/3068 # suggested in https://github.com/rubygems/rubygems/issues/3068#issuecomment-574775885 diff --git a/CMakeLists.txt b/CMakeLists.txt index 4d3ad184b..afbd63801 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -109,24 +109,8 @@ set (build_warnings "" CACHE INTERNAL "build warnings" FORCE) set (sdf_cmake_dir ${PROJECT_SOURCE_DIR}/cmake CACHE PATH "Location of CMake scripts") -include (${sdf_cmake_dir}/SDFUtils.cmake) - -if (UNIX) - option (USE_EXTERNAL_TINYXML "Use external TinyXML" ON) -elseif(WIN32) - option (USE_EXTERNAL_TINYXML "Use external TinyXML" OFF) -else() - message (STATUS "Unknown platform") - BUILD_ERROR("Unknown platform") -endif() - message (STATUS "\n\n====== Finding 3rd Party Packages ======") - # Use of tinyxml. System installation on UNIX. Internal copy on WIN -if (USE_EXTERNAL_TINYXML) - message (STATUS "Using system tinyxml") -else() - message (STATUS "Using internal tinyxml code") -endif() +include (${sdf_cmake_dir}/SDFUtils.cmake) include (${sdf_cmake_dir}/SearchForStuff.cmake) message (STATUS "----------------------------------------\n") diff --git a/Changelog.md b/Changelog.md index 411e079a9..b1dc9c2b4 100644 --- a/Changelog.md +++ b/Changelog.md @@ -4,6 +4,9 @@ ### libsdformat 10.0.0 (202X-XX-XX) +1. Migrate to using TinyXML2. + * [Pull request 264](https://github.com/osrf/sdformat/pull/264) + 1. Enforce minimum/maximum values specified in SDFormat description files. * [Pull request 303](https://github.com/osrf/sdformat/pull/303) diff --git a/Migration.md b/Migration.md index c53dbef4f..983d47648 100644 --- a/Migration.md +++ b/Migration.md @@ -16,6 +16,9 @@ but with improved human-readability.. ### Modifications +1. + Depend on tinyxml2 instead of tinyxml for XML parsing. + + [Pull request 264](https://github.com/osrf/sdformat/pull/264) + 1. + Minimum/maximum values specified in SDFormat description files are now enforced + [Pull request 303](https://github.com/osrf/sdformat/pull/303) diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml index b2ebf1b7e..e1dad3b7d 100644 --- a/bitbucket-pipelines.yml +++ b/bitbucket-pipelines.yml @@ -10,7 +10,7 @@ pipelines: - sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' - wget http://packages.osrfoundation.org/gazebo.key -O - | apt-key add - - apt-get update - - apt -y install cmake build-essential curl git libtinyxml-dev libxml2-utils ruby-dev python-psutil cppcheck + - apt -y install cmake build-essential curl git libtinyxml2-dev libxml2-utils ruby-dev python-psutil cppcheck - gcc -v - g++ -v - gcov -v diff --git a/cmake/Modules/FindTinyXML2.cmake b/cmake/Modules/FindTinyXML2.cmake new file mode 100644 index 000000000..6976dee02 --- /dev/null +++ b/cmake/Modules/FindTinyXML2.cmake @@ -0,0 +1,42 @@ +# CMake Logic to find system TinyXML2, sourced from: +# ros2/tinyxml2_vendor +# https://github.com/ros2/tinyxml2_vendor/commit/fde8000d31d68ff555431d63af3c324afba9f117#diff-120198e331f1dd3e7806c31af0cfb425 + +# The CMake Logic here is licensed under Apache License 2.0 +# TinyXML2 itself is licensed under the zlib License + +# TinyXML2_FOUND +# TinyXML2_INCLUDE_DIRS +# TinyXML2_LIBRARIES + +# try to find the CMake config file for TinyXML2 first +find_package(TinyXML2 CONFIG QUIET) +if(TinyXML2_FOUND) + message(STATUS "Found TinyXML2 via Config file: ${TinyXML2_DIR}") + if(NOT TINYXML2_LIBRARY) + # in this case, we're probably using TinyXML2 version 5.0.0 or greater + # in which case tinyxml2 is an exported target and we should use that + if(TARGET tinyxml2) + set(TINYXML2_LIBRARY tinyxml2) + elseif(TARGET tinyxml2::tinyxml2) + set(TINYXML2_LIBRARY tinyxml2::tinyxml2) + endif() + endif() +else() + find_path(TINYXML2_INCLUDE_DIR NAMES tinyxml2.h) + + find_library(TINYXML2_LIBRARY tinyxml2) + + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(TinyXML2 DEFAULT_MSG TINYXML2_LIBRARY TINYXML2_INCLUDE_DIR) + + mark_as_advanced(TINYXML2_INCLUDE_DIR TINYXML2_LIBRARY) +endif() + +# Set mixed case INCLUDE_DIRS and LIBRARY variables from upper case ones. +if(NOT TinyXML2_INCLUDE_DIRS) + set(TinyXML2_INCLUDE_DIRS ${TINYXML2_INCLUDE_DIR}) +endif() +if(NOT TinyXML2_LIBRARIES) + set(TinyXML2_LIBRARIES ${TINYXML2_LIBRARY}) +endif() diff --git a/cmake/SDFUtils.cmake b/cmake/SDFUtils.cmake index 16155dcce..525c4d4c6 100644 --- a/cmake/SDFUtils.cmake +++ b/cmake/SDFUtils.cmake @@ -135,18 +135,9 @@ macro (sdf_build_tests) string(REGEX REPLACE ".cc" "" BINARY_NAME ${GTEST_SOURCE_file}) set(BINARY_NAME ${TEST_TYPE}_${BINARY_NAME}) - if (NOT USE_EXTERNAL_TINYXML) - set(tinyxml_SRC - ${PROJECT_SOURCE_DIR}/src/win/tinyxml/tinystr.cpp - ${PROJECT_SOURCE_DIR}/src/win/tinyxml/tinyxmlerror.cpp - ${PROJECT_SOURCE_DIR}/src/win/tinyxml/tinyxml.cpp - ${PROJECT_SOURCE_DIR}/src/win/tinyxml/tinyxmlparser.cpp) - endif() - add_executable(${BINARY_NAME} ${GTEST_SOURCE_file} ${SDF_BUILD_TESTS_EXTRA_EXE_SRCS} - ${tinyxml_SRC} ) add_dependencies(${BINARY_NAME} @@ -154,11 +145,7 @@ macro (sdf_build_tests) ) link_directories(${IGNITION-MATH_LIBRARY_DIRS}) - - if (USE_EXTERNAL_TINYXML) - target_link_libraries(${BINARY_NAME} PRIVATE - ${tinyxml_LIBRARIES}) - endif() + target_link_libraries(${BINARY_NAME} ${tinyxml2_LIBRARIES}) if (UNIX) target_link_libraries(${BINARY_NAME} PRIVATE diff --git a/cmake/SearchForStuff.cmake b/cmake/SearchForStuff.cmake index 965f1ecf7..2970e2188 100644 --- a/cmake/SearchForStuff.cmake +++ b/cmake/SearchForStuff.cmake @@ -5,36 +5,10 @@ include (${project_cmake_dir}/TargetArch.cmake) target_architecture(ARCH) message(STATUS "Building for arch: ${ARCH}") -if (USE_EXTERNAL_TINYXML) - ################################################# - # Find tinyxml. Only debian distributions package tinyxml with a pkg-config - # Use pkg_check_modules and fallback to manual detection (needed, at least, for MacOS) - pkg_check_modules(tinyxml tinyxml) - if (NOT tinyxml_FOUND) - find_path (tinyxml_INCLUDE_DIRS tinyxml.h ${tinyxml_INCLUDE_DIRS} ENV CPATH) - find_library(tinyxml_LIBRARIES NAMES tinyxml) - set (tinyxml_FAIL False) - if (NOT tinyxml_INCLUDE_DIRS) - message (STATUS "Looking for tinyxml headers - not found") - set (tinyxml_FAIL True) - endif() - if (NOT tinyxml_LIBRARIES) - message (STATUS "Looking for tinyxml library - not found") - set (tinyxml_FAIL True) - endif() - endif() - - if (tinyxml_FAIL) - message (STATUS "Looking for tinyxml.h - not found") - BUILD_ERROR("Missing: tinyxml") - endif() -else() - # Needed in WIN32 since in UNIX the flag is added in the code installed - add_definitions(-DTIXML_USE_STL) - include_directories (${PROJECT_SOURCE_DIR}/src/win/tinyxml) - set (tinyxml_LIBRARIES "tinyxml") - set (tinyxml_LIBRARY_DIRS "") -endif() +################################################# +# Find tinyxml2. +list(INSERT CMAKE_MODULE_PATH 0 "${CMAKE_CURRENT_SOURCE_DIR}/cmake/Modules") +find_package(TinyXML2 REQUIRED) ################################################ # Find urdfdom parser. Logic: diff --git a/examples/simple.sdf b/examples/simple.sdf index 76aee66c8..f54e96328 100644 --- a/examples/simple.sdf +++ b/examples/simple.sdf @@ -3,4 +3,4 @@ -" + diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index bb8c7d1b5..ad9467c47 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -8,10 +8,6 @@ if (NOT USE_INTERNAL_URDF) link_directories(${URDF_LIBRARY_DIRS}) endif() -if (USE_EXTERNAL_TINYXML) - link_directories(${tinyxml_LIBRARY_DIRS}) -endif() - set (sources Actor.cc AirPressure.cc @@ -62,22 +58,10 @@ set (sources Utils.cc Visual.cc World.cc + XmlUtils.cc ) include_directories(${CMAKE_CURRENT_SOURCE_DIR}) -if (USE_EXTERNAL_TINYXML) - include_directories(${tinyxml_INCLUDE_DIRS}) -else() - set(sources ${sources} - win/tinyxml/tinystr.cpp - win/tinyxml/tinyxmlerror.cpp - win/tinyxml/tinyxml.cpp - win/tinyxml/tinyxmlparser.cpp) - - install (FILES win/tinyxml/tinyxml.h - DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/sdformat-${SDF_VERSION}) -endif() - if (USE_INTERNAL_URDF) include_directories(${CMAKE_CURRENT_SOURCE_DIR}/urdf) set(sources ${sources} @@ -153,18 +137,23 @@ if (BUILD_SDF_TEST) sdf_build_tests(Utils_TEST.cc) endif() + if (NOT WIN32) + set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS XmlUtils.cc) + sdf_build_tests(XmlUtils_TEST.cc) + endif() + if (NOT WIN32) set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS FrameSemantics.cc) sdf_build_tests(FrameSemantics_TEST.cc) endif() if (NOT WIN32) - set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS Converter.cc EmbeddedSdf.cc) + set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS Converter.cc EmbeddedSdf.cc XmlUtils.cc) sdf_build_tests(Converter_TEST.cc) endif() if (NOT WIN32) - set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS SDFExtension.cc parser_urdf.cc) + set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS SDFExtension.cc parser_urdf.cc XmlUtils.cc) sdf_build_tests(parser_urdf_TEST.cc) if (NOT USE_INTERNAL_URDF) target_compile_options(UNIT_parser_urdf_TEST PRIVATE ${URDF_CFLAGS}) @@ -178,7 +167,13 @@ endif() sdf_add_library(${sdf_target} ${sources}) target_compile_features(${sdf_target} PUBLIC cxx_std_17) -target_link_libraries(${sdf_target} PUBLIC ${IGNITION-MATH_LIBRARIES}) +target_link_libraries(${sdf_target} PUBLIC + ${IGNITION-MATH_LIBRARIES} + ${TinyXML2_LIBRARIES}) + +if (WIN32) + target_compile_definitions(${sdf_target} PRIVATE URDFDOM_STATIC) +endif() target_include_directories(${sdf_target} PUBLIC @@ -187,14 +182,6 @@ target_include_directories(${sdf_target} $ ) -if (USE_EXTERNAL_TINYXML) - target_link_libraries(${sdf_target} PRIVATE ${tinyxml_LIBRARIES}) -else() - # Ignore the warnings from the internal library - set_target_properties(sdformat${SDF_MAJOR_VERSION} PROPERTIES - LINK_FLAGS "/IGNORE:4049 /IGNORE:4217") -endif() - message (STATUS "URDF_LIBRARY_DIRS=${URDF_LIBRARY_DIRS}") message (STATUS "URDF_LIBRARIES=${URDF_LIBRARIES}") diff --git a/src/Converter.cc b/src/Converter.cc index 4dc66a1d7..dff989ad2 100644 --- a/src/Converter.cc +++ b/src/Converter.cc @@ -30,6 +30,7 @@ #include "Converter.hh" #include "EmbeddedSdf.hh" +#include "XmlUtils.hh" using namespace sdf; @@ -42,12 +43,13 @@ bool EndsWith(const std::string& _a, const std::string& _b) } ///////////////////////////////////////////////// -bool Converter::Convert(TiXmlDocument *_doc, const std::string &_toVersion, +bool Converter::Convert(tinyxml2::XMLDocument *_doc, + const std::string &_toVersion, bool _quiet) { SDF_ASSERT(_doc != nullptr, "SDF XML doc is NULL"); - TiXmlElement *elem = _doc->FirstChildElement("sdf"); + tinyxml2::XMLElement *elem = _doc->FirstChildElement("sdf"); // Check that the element exists if (!elem) @@ -77,7 +79,7 @@ bool Converter::Convert(TiXmlDocument *_doc, const std::string &_toVersion, << " $ gz sdf -c [sdf_file]\n"; } - elem->SetAttribute("version", _toVersion); + elem->SetAttribute("version", _toVersion.c_str()); // The conversion recipes within the embedded files database are named, e.g., // "1.8/1_7.convert" to upgrade from 1.7 to 1.8. @@ -107,12 +109,12 @@ bool Converter::Convert(TiXmlDocument *_doc, const std::string &_toVersion, } // Parse and apply the conversion XML. - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(convertXml); if (xmlDoc.Error()) { sdferr << "Error parsing XML from string: " - << xmlDoc.ErrorDesc() << '\n'; + << xmlDoc.ErrorStr() << '\n'; return false; } ConvertImpl(elem, xmlDoc.FirstChildElement("convert")); @@ -130,7 +132,8 @@ bool Converter::Convert(TiXmlDocument *_doc, const std::string &_toVersion, } ///////////////////////////////////////////////// -void Converter::Convert(TiXmlDocument *_doc, TiXmlDocument *_convertDoc) +void Converter::Convert(tinyxml2::XMLDocument *_doc, + tinyxml2::XMLDocument *_convertDoc) { SDF_ASSERT(_doc != NULL, "SDF XML doc is NULL"); SDF_ASSERT(_convertDoc != NULL, "Convert XML doc is NULL"); @@ -139,28 +142,28 @@ void Converter::Convert(TiXmlDocument *_doc, TiXmlDocument *_convertDoc) } ///////////////////////////////////////////////// -void Converter::ConvertDescendantsImpl(TiXmlElement *_e, TiXmlElement *_c) +void Converter::ConvertDescendantsImpl(tinyxml2::XMLElement *_e, + tinyxml2::XMLElement *_c) { if (!_c->Attribute("descendant_name")) { return; } - if (_e->ValueStr() == "plugin") + if (strcmp(_e->Name(), "plugin") == 0) { return; } - if (_e->ValueStr().find(":") != std::string::npos) + if (strchr(_e->Name(), ':') != nullptr) { return; } - std::string name = _c->Attribute("descendant_name"); - TiXmlElement *e = _e->FirstChildElement(); + tinyxml2::XMLElement *e = _e->FirstChildElement(); while (e) { - if (name == e->ValueStr()) + if (strcmp(e->Name(), _c->Attribute("descendant_name")) == 0) { ConvertImpl(e, _c); } @@ -170,19 +173,20 @@ void Converter::ConvertDescendantsImpl(TiXmlElement *_e, TiXmlElement *_c) } ///////////////////////////////////////////////// -void Converter::ConvertImpl(TiXmlElement *_elem, TiXmlElement *_convert) +void Converter::ConvertImpl(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_convert) { SDF_ASSERT(_elem != NULL, "SDF element is NULL"); SDF_ASSERT(_convert != NULL, "Convert element is NULL"); CheckDeprecation(_elem, _convert); - for (TiXmlElement *convertElem = _convert->FirstChildElement("convert"); + for (auto *convertElem = _convert->FirstChildElement("convert"); convertElem; convertElem = convertElem->NextSiblingElement("convert")) { if (convertElem->Attribute("name")) { - TiXmlElement *elem = _elem->FirstChildElement( + tinyxml2::XMLElement *elem = _elem->FirstChildElement( convertElem->Attribute("name")); while (elem) { @@ -196,48 +200,51 @@ void Converter::ConvertImpl(TiXmlElement *_elem, TiXmlElement *_convert) } } - for (TiXmlElement *childElem = _convert->FirstChildElement(); + for (tinyxml2::XMLElement *childElem = _convert->FirstChildElement(); childElem; childElem = childElem->NextSiblingElement()) { - if (childElem->ValueStr() == "rename") + const auto name = std::string(childElem->Name()); + + if (name == "rename") { Rename(_elem, childElem); } - else if (childElem->ValueStr() == "copy") + else if (name == "copy") { Move(_elem, childElem, true); } - else if (childElem->ValueStr() == "map") + else if (name == "map") { Map(_elem, childElem); } - else if (childElem->ValueStr() == "move") + else if (name == "move") { Move(_elem, childElem, false); } - else if (childElem->ValueStr() == "add") + else if (name == "add") { Add(_elem, childElem); } - else if (childElem->ValueStr() == "remove") + else if (name == "remove") { Remove(_elem, childElem); } - else if (childElem->ValueStr() != "convert") + else if (name != "convert") { - sdferr << "Unknown convert element[" << childElem->ValueStr() << "]\n"; + sdferr << "Unknown convert element[" << name << "]\n"; } } } ///////////////////////////////////////////////// -void Converter::Rename(TiXmlElement *_elem, TiXmlElement *_renameElem) +void Converter::Rename(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_renameElem) { SDF_ASSERT(_elem != NULL, "SDF element is NULL"); SDF_ASSERT(_renameElem != NULL, "Rename element is NULL"); - TiXmlElement *fromConvertElem = _renameElem->FirstChildElement("from"); - TiXmlElement *toConvertElem = _renameElem->FirstChildElement("to"); + auto *fromConvertElem = _renameElem->FirstChildElement("from"); + auto *toConvertElem = _renameElem->FirstChildElement("to"); const char *fromElemName = fromConvertElem->Attribute("element"); const char *fromAttrName = fromConvertElem->Attribute("attribute"); @@ -257,44 +264,33 @@ void Converter::Rename(TiXmlElement *_elem, TiXmlElement *_renameElem) return; } - TiXmlElement *replaceTo = new TiXmlElement(toElemName); + auto *doc = _elem->GetDocument(); + tinyxml2::XMLElement *replaceTo = doc->NewElement(toElemName); if (toAttrName) { replaceTo->SetAttribute(toAttrName, value); } else { - TiXmlText *text = new TiXmlText(value); - // The tinyxml function LinkEndChild takes the pointer and takes ownership - // of the memory, so it is responsible for freeing it later. + tinyxml2::XMLText *text = doc->NewText(value); replaceTo->LinkEndChild(text); } if (fromElemName) { - TiXmlElement *replaceFrom = _elem->FirstChildElement(fromElemName); - if (_elem->ReplaceChild(replaceFrom, *replaceTo) == nullptr) - { - sdferr << "Failed to rename element\n"; - // fall through so we can reclaim memory - } - - // In this case, the tinyxml function ReplaceChild does a deep copy of the - // node that is passed in, so we want to free it here. - delete replaceTo; + tinyxml2::XMLElement *replaceFrom = _elem->FirstChildElement(fromElemName); + _elem->InsertAfterChild(replaceFrom, replaceTo); + _elem->DeleteChild(replaceFrom); } else if (fromAttrName) { - _elem->RemoveAttribute(fromAttrName); - // In this case, the tinyxml function LinkEndChild just takes the pointer - // and takes ownership of the memory, so it is responsible for freeing it - // later. + _elem->DeleteAttribute(fromAttrName); _elem->LinkEndChild(replaceTo); } } ///////////////////////////////////////////////// -void Converter::Add(TiXmlElement *_elem, TiXmlElement *_addElem) +void Converter::Add(tinyxml2::XMLElement *_elem, tinyxml2::XMLElement *_addElem) { SDF_ASSERT(_elem != NULL, "SDF element is NULL"); SDF_ASSERT(_addElem != NULL, "Add element is NULL"); @@ -324,10 +320,11 @@ void Converter::Add(TiXmlElement *_elem, TiXmlElement *_addElem) } else { - TiXmlElement *addElem = new TiXmlElement(elementName); + auto *doc = _elem->GetDocument(); + tinyxml2::XMLElement *addElem = doc->NewElement(elementName); if (value) { - TiXmlText *addText = new TiXmlText(value); + tinyxml2::XMLText *addText = doc->NewText(value); addElem->LinkEndChild(addText); } _elem->LinkEndChild(addElem); @@ -335,7 +332,8 @@ void Converter::Add(TiXmlElement *_elem, TiXmlElement *_addElem) } ///////////////////////////////////////////////// -void Converter::Remove(TiXmlElement *_elem, TiXmlElement *_removeElem) +void Converter::Remove(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_removeElem) { SDF_ASSERT(_elem != NULL, "SDF element is NULL"); SDF_ASSERT(_removeElem != NULL, "Move element is NULL"); @@ -352,27 +350,28 @@ void Converter::Remove(TiXmlElement *_elem, TiXmlElement *_removeElem) if (attributeName) { - _elem->RemoveAttribute(attributeName); + _elem->DeleteAttribute(attributeName); } else { - TiXmlElement *childElem = _elem->FirstChildElement(elementName); + tinyxml2::XMLElement *childElem = _elem->FirstChildElement(elementName); + while (childElem) { - _elem->RemoveChild(childElem); + _elem->DeleteChild(childElem); childElem = _elem->FirstChildElement(elementName); } } } ///////////////////////////////////////////////// -void Converter::Map(TiXmlElement *_elem, TiXmlElement *_mapElem) +void Converter::Map(tinyxml2::XMLElement *_elem, tinyxml2::XMLElement *_mapElem) { SDF_ASSERT(_elem != nullptr, "SDF element is nullptr"); SDF_ASSERT(_mapElem != nullptr, "Map element is nullptr"); - TiXmlElement *fromConvertElem = _mapElem->FirstChildElement("from"); - TiXmlElement *toConvertElem = _mapElem->FirstChildElement("to"); + tinyxml2::XMLElement *fromConvertElem = _mapElem->FirstChildElement("from"); + tinyxml2::XMLElement *toConvertElem = _mapElem->FirstChildElement("to"); if (!fromConvertElem) { @@ -401,8 +400,8 @@ void Converter::Map(TiXmlElement *_elem, TiXmlElement *_mapElem) // create map of input and output values std::map valueMap; - TiXmlElement *fromValueElem = fromConvertElem->FirstChildElement("value"); - TiXmlElement *toValueElem = toConvertElem->FirstChildElement("value"); + auto *fromValueElem = fromConvertElem->FirstChildElement("value"); + auto *toValueElem = toConvertElem->FirstChildElement("value"); if (!fromValueElem) { sdferr << "Map: element requires at least one element.\n"; @@ -455,10 +454,10 @@ void Converter::Map(TiXmlElement *_elem, TiXmlElement *_mapElem) // empty string. Thus we don't check if the fromTokens or toTokens are empty. // get value of the 'from' element/attribute - TiXmlElement *fromElem = _elem; + tinyxml2::XMLElement *fromElem = _elem; for (unsigned int i = 0; i < fromTokens.size()-1; ++i) { - fromElem = fromElem->FirstChildElement(fromTokens[i]); + fromElem = fromElem->FirstChildElement(fromTokens[i].c_str()); if (!fromElem) { // Return when the tokens don't match. Don't output an error message @@ -496,11 +495,11 @@ void Converter::Map(TiXmlElement *_elem, TiXmlElement *_mapElem) // check if destination elements before leaf exist and create if necessary unsigned int newDirIndex = 0; - TiXmlElement *toElem = _elem; - TiXmlElement *childElem = NULL; + tinyxml2::XMLElement *toElem = _elem; + tinyxml2::XMLElement *childElem = NULL; for (unsigned int i = 0; i < toTokens.size()-1; ++i) { - childElem = toElem->FirstChildElement(toTokens[i]); + childElem = toElem->FirstChildElement(toTokens[i].c_str()); if (!childElem) { newDirIndex = i; @@ -519,6 +518,8 @@ void Converter::Map(TiXmlElement *_elem, TiXmlElement *_mapElem) } bool toAttribute = toLeaf[0] == '@'; + auto *doc = _elem->GetDocument(); + // found elements in 'to' string that are not present, so create new // elements if they aren't empty if (!childElem) @@ -532,7 +533,7 @@ void Converter::Map(TiXmlElement *_elem, TiXmlElement *_mapElem) return; } - TiXmlElement *newElem = new TiXmlElement(toTokens[newDirIndex]); + auto *newElem = doc->NewElement(toTokens[newDirIndex].c_str()); toElem->LinkEndChild(newElem); toElem = newElem; newDirIndex++; @@ -545,20 +546,21 @@ void Converter::Map(TiXmlElement *_elem, TiXmlElement *_mapElem) } else { - TiXmlText *text = new TiXmlText(toValue); + tinyxml2::XMLText *text = doc->NewText(toValue); toElem->LinkEndChild(text); } } ///////////////////////////////////////////////// -void Converter::Move(TiXmlElement *_elem, TiXmlElement *_moveElem, +void Converter::Move(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_moveElem, const bool _copy) { SDF_ASSERT(_elem != NULL, "SDF element is NULL"); SDF_ASSERT(_moveElem != NULL, "Move element is NULL"); - TiXmlElement *fromConvertElem = _moveElem->FirstChildElement("from"); - TiXmlElement *toConvertElem = _moveElem->FirstChildElement("to"); + tinyxml2::XMLElement *fromConvertElem = _moveElem->FirstChildElement("from"); + tinyxml2::XMLElement *toConvertElem = _moveElem->FirstChildElement("to"); const char *fromElemStr = fromConvertElem->Attribute("element"); const char *fromAttrStr = fromConvertElem->Attribute("attribute"); @@ -593,10 +595,10 @@ void Converter::Move(TiXmlElement *_elem, TiXmlElement *_moveElem, // empty string. Thus we don't check if the fromTokens or toTokens are empty. // get value of the 'from' element/attribute - TiXmlElement *fromElem = _elem; + tinyxml2::XMLElement *fromElem = _elem; for (unsigned int i = 0; i < fromTokens.size()-1; ++i) { - fromElem = fromElem->FirstChildElement(fromTokens[i]); + fromElem = fromElem->FirstChildElement(fromTokens[i].c_str()); if (!fromElem) { // Return when the tokens don't match. Don't output an error message @@ -606,16 +608,16 @@ void Converter::Move(TiXmlElement *_elem, TiXmlElement *_moveElem, } const char *fromName = fromTokens.back().c_str(); - const char *value = NULL; + const char *value = nullptr; unsigned int newDirIndex = 0; // get the new element/attribute name const char *toName = toTokens.back().c_str(); - TiXmlElement *toElem = _elem; - TiXmlElement *childElem = NULL; + tinyxml2::XMLElement *toElem = _elem; + tinyxml2::XMLElement *childElem = nullptr; for (unsigned int i = 0; i < toTokens.size()-1; ++i) { - childElem = toElem->FirstChildElement(toTokens[i]); + childElem = toElem->FirstChildElement(toTokens[i].c_str()); if (!childElem) { newDirIndex = i; @@ -628,10 +630,11 @@ void Converter::Move(TiXmlElement *_elem, TiXmlElement *_moveElem, // elements if (!childElem) { - int offset = toElemStr != NULL && toAttrStr != NULL ? 0 : 1; + int offset = toElemStr != nullptr && toAttrStr != nullptr ? 0 : 1; while (newDirIndex < (toTokens.size()-offset)) { - TiXmlElement *newElem = new TiXmlElement(toTokens[newDirIndex]); + auto *doc = toElem->GetDocument(); + auto *newElem = doc->NewElement(toTokens[newDirIndex].c_str()); toElem->LinkEndChild(newElem); toElem = newElem; newDirIndex++; @@ -642,7 +645,7 @@ void Converter::Move(TiXmlElement *_elem, TiXmlElement *_moveElem, // be specified in the sdf. if (fromElemStr) { - TiXmlElement *moveFrom = fromElem->FirstChildElement(fromName); + tinyxml2::XMLElement *moveFrom = fromElem->FirstChildElement(fromName); // No matching element, so return. if (!moveFrom) @@ -652,30 +655,32 @@ void Converter::Move(TiXmlElement *_elem, TiXmlElement *_moveElem, if (toElemStr && !toAttrStr) { - TiXmlElement *moveTo = static_cast(moveFrom->Clone()); + tinyxml2::XMLNode *cloned = DeepClone(moveFrom->GetDocument(), moveFrom); + tinyxml2::XMLElement *moveTo = static_cast(cloned); + moveTo->SetValue(toName); toElem->LinkEndChild(moveTo); } else { - value = GetValue(fromName, NULL, fromElem); + value = GetValue(fromName, nullptr, fromElem); if (!value) { return; } std::string valueStr = value; - toElem->SetAttribute(toAttrStr, valueStr); + toElem->SetAttribute(toAttrStr, valueStr.c_str()); } if (!_copy) { - fromElem->RemoveChild(moveFrom); + fromElem->DeleteChild(moveFrom); } } else if (fromAttrStr) { - value = GetValue(NULL, fromName, fromElem); + value = GetValue(nullptr, fromName, fromElem); if (!value) { @@ -686,26 +691,27 @@ void Converter::Move(TiXmlElement *_elem, TiXmlElement *_moveElem, if (toElemStr) { - TiXmlElement *moveTo = new TiXmlElement(toName); - TiXmlText *text = new TiXmlText(valueStr); + auto *doc = toElem->GetDocument(); + tinyxml2::XMLElement *moveTo = doc->NewElement(toName); + tinyxml2::XMLText *text = doc->NewText(valueStr.c_str()); moveTo->LinkEndChild(text); toElem->LinkEndChild(moveTo); } else if (toAttrStr) { - toElem->SetAttribute(toName, valueStr); + toElem->SetAttribute(toName, valueStr.c_str()); } if (!_copy && fromAttrStr) { - fromElem->RemoveAttribute(fromName); + fromElem->DeleteAttribute(fromName); } } } ///////////////////////////////////////////////// const char *Converter::GetValue(const char *_valueElem, const char *_valueAttr, - TiXmlElement *_elem) + tinyxml2::XMLElement *_elem) { if (_valueElem) { @@ -733,10 +739,11 @@ const char *Converter::GetValue(const char *_valueElem, const char *_valueAttr, } ///////////////////////////////////////////////// -void Converter::CheckDeprecation(TiXmlElement *_elem, TiXmlElement *_convert) +void Converter::CheckDeprecation(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_convert) { // Process deprecated elements - for (TiXmlElement *deprecatedElem = _convert->FirstChildElement("deprecated"); + for (auto *deprecatedElem = _convert->FirstChildElement("deprecated"); deprecatedElem; deprecatedElem = deprecatedElem->NextSiblingElement("deprecated")) { @@ -744,13 +751,13 @@ void Converter::CheckDeprecation(TiXmlElement *_elem, TiXmlElement *_convert) std::vector valueSplit = split(value, "/"); bool found = false; - TiXmlElement *e = _elem; + tinyxml2::XMLElement *e = _elem; std::ostringstream stream; std::string prefix = ""; for (unsigned int i = 0; i < valueSplit.size() && !found; ++i) { - if (e->FirstChildElement(valueSplit[i])) + if (e->FirstChildElement(valueSplit[i].c_str())) { if (stream.str().size() != 0) { @@ -759,9 +766,9 @@ void Converter::CheckDeprecation(TiXmlElement *_elem, TiXmlElement *_convert) } stream << prefix << "<" << valueSplit[i]; - e = e->FirstChildElement(valueSplit[i]); + e = e->FirstChildElement(valueSplit[i].c_str()); } - else if (e->Attribute(valueSplit[i])) + else if (e->Attribute(valueSplit[i].c_str())) { stream << " " << valueSplit[i] << "='" << e->Attribute(valueSplit[i].c_str()) << "'"; diff --git a/src/Converter.hh b/src/Converter.hh index 3237f2a15..c5f7c6e7c 100644 --- a/src/Converter.hh +++ b/src/Converter.hh @@ -17,7 +17,7 @@ #ifndef _SDF_CONVERTER_HH_ #define _SDF_CONVERTER_HH_ -#include +#include #include @@ -37,7 +37,7 @@ namespace sdf /// \param[in] _doc SDF xml doc /// \param[in] _toVersion Version number in string format /// \param[in] _quiet False to be more verbose - public: static bool Convert(TiXmlDocument *_doc, + public: static bool Convert(tinyxml2::XMLDocument *_doc, const std::string &_toVersion, bool _quiet = false); @@ -47,38 +47,38 @@ namespace sdf /// given Convert file. /// \param[in] _doc SDF xml doc /// \param[in] _convertDoc Convert xml doc - public: static void Convert(TiXmlDocument *_doc, - TiXmlDocument *_convertDoc); + public: static void Convert(tinyxml2::XMLDocument *_doc, + tinyxml2::XMLDocument *_convertDoc); /// \endcond /// \brief Implementation of Convert functionality. /// \param[in] _elem SDF xml element tree to convert. /// \param[in] _convert Convert xml element tree. - private: static void ConvertImpl(TiXmlElement *_elem, - TiXmlElement *_convert); + private: static void ConvertImpl(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_convert); /// \brief Recursive helper function for ConvertImpl that converts /// elements named by the descendant_name attribute. /// \param[in] _e SDF xml element tree to convert. /// \param[in] _c Convert xml element tree. - private: static void ConvertDescendantsImpl(TiXmlElement *_e, - TiXmlElement *_c); + private: static void ConvertDescendantsImpl(tinyxml2::XMLElement *_e, + tinyxml2::XMLElement *_c); /// \brief Rename an element or attribute. /// \param[in] _elem The element to be renamed, or the element which /// has the attribute to be renamed. /// \param[in] _renameElem A 'convert' element that describes the rename /// operation. - private: static void Rename(TiXmlElement *_elem, - TiXmlElement *_renameElem); + private: static void Rename(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_renameElem); /// \brief Map values from one element or attribute to another. /// \param[in] _elem Ancestor element of the element or attribute to /// be mapped. /// \param[in] _mapElem A 'convert' element that describes the map /// operation. - private: static void Map(TiXmlElement *_elem, - TiXmlElement *_mapElem); + private: static void Map(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_mapElem); /// \brief Move an element or attribute within a common ancestor element. /// \param[in] _elem Ancestor element of the element or attribute to @@ -86,28 +86,29 @@ namespace sdf /// \param[in] _moveElem A 'convert' element that describes the move /// operation. /// \param[in] _copy True to copy the element - private: static void Move(TiXmlElement *_elem, - TiXmlElement *_moveElem, + private: static void Move(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_moveElem, const bool _copy); /// \brief Add an element or attribute to an element. /// \param[in] _elem The element to receive the value. /// \param[in] _addElem A 'convert' element that describes the add /// operation. - private: static void Add(TiXmlElement *_elem, - TiXmlElement *_addElem); + private: static void Add(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_addElem); /// \brief Remove an element. /// \param[in] _elem The element that has the _removeElem child. /// \param[in] _removeElem The element to remove. - private: static void Remove(TiXmlElement *_elem, TiXmlElement *_removeElem); + private: static void Remove(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_removeElem); private: static const char *GetValue(const char *_valueElem, const char *_valueAttr, - TiXmlElement *_elem); + tinyxml2::XMLElement *_elem); - private: static void CheckDeprecation(TiXmlElement *_elem, - TiXmlElement *_convert); + private: static void CheckDeprecation(tinyxml2::XMLElement *_elem, + tinyxml2::XMLElement *_convert); }; } } diff --git a/src/Converter_TEST.cc b/src/Converter_TEST.cc index cdee13f2e..131535622 100644 --- a/src/Converter_TEST.cc +++ b/src/Converter_TEST.cc @@ -22,6 +22,8 @@ #include "sdf/Filesystem.hh" #include "Converter.hh" +#include "XmlUtils.hh" + #include "test_config.h" //////////////////////////////////////////////////// @@ -66,20 +68,20 @@ TEST(Converter, MoveElemElem) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test moving from elem to elem // Set up a convert file @@ -92,15 +94,15 @@ TEST(Converter, MoveElemElem) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemC")); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemE")); std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); @@ -119,7 +121,7 @@ TEST(Converter, MoveElemAttr) std::string xmlString = getXmlString(); // Test moving from elem to attr - TiXmlDocument xmlDoc2; + tinyxml2::XMLDocument xmlDoc2; xmlDoc2.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -130,21 +132,21 @@ TEST(Converter, MoveElemAttr) << " " << " " << ""; - TiXmlDocument convertXmlDoc2; + tinyxml2::XMLDocument convertXmlDoc2; convertXmlDoc2.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc2, &convertXmlDoc2); - TiXmlElement *convertedElem = xmlDoc2.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc2.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); EXPECT_NE(nullptr, convertedElem->Attribute("attrE")); std::string attrValue = convertedElem->Attribute("attrE"); EXPECT_EQ(attrValue, "D"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_FALSE(convertedElem->FirstChildElement("elemD")); } @@ -157,7 +159,7 @@ TEST(Converter, MoveAttrAttr) std::string xmlString = getXmlString(); // Test moving from attr to attr - TiXmlDocument xmlDoc3; + tinyxml2::XMLDocument xmlDoc3; xmlDoc3.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -168,25 +170,25 @@ TEST(Converter, MoveAttrAttr) << " " << " " << ""; - TiXmlDocument convertXmlDoc3; + tinyxml2::XMLDocument convertXmlDoc3; convertXmlDoc3.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc3, &convertXmlDoc3); - TiXmlElement *convertedElem = xmlDoc3.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc3.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); EXPECT_NE(nullptr, convertedElem->Attribute("attrE")); std::string attrValue = convertedElem->Attribute("attrE"); EXPECT_EQ(attrValue, "C"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_FALSE(convertedElem->Attribute("attrC")); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -198,7 +200,7 @@ TEST(Converter, MoveAttrElem) std::string xmlString = getXmlString(); // Test moving from attr to elem - TiXmlDocument xmlDoc4; + tinyxml2::XMLDocument xmlDoc4; xmlDoc4.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -209,15 +211,15 @@ TEST(Converter, MoveAttrElem) << " " << " " << ""; - TiXmlDocument convertXmlDoc4; + tinyxml2::XMLDocument convertXmlDoc4; convertXmlDoc4.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc4, &convertXmlDoc4); - TiXmlElement *convertedElem = xmlDoc4.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc4.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemE")); std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); EXPECT_EQ(elemValue, "C"); @@ -227,7 +229,7 @@ TEST(Converter, MoveAttrElem) EXPECT_FALSE(convertedElem->Attribute("attrC")); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -239,7 +241,7 @@ TEST(Converter, MoveElemElemMultipleLevels) std::string xmlString = getXmlString(); // Test moving from elem to elem across multiple levels - TiXmlDocument xmlDoc5; + tinyxml2::XMLDocument xmlDoc5; xmlDoc5.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -248,12 +250,12 @@ TEST(Converter, MoveElemElemMultipleLevels) << " " << " " << ""; - TiXmlDocument convertXmlDoc5; + tinyxml2::XMLDocument convertXmlDoc5; convertXmlDoc5.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc5, &convertXmlDoc5); - TiXmlElement *convertedElem = xmlDoc5.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc5.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemE")); std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); EXPECT_EQ(elemValue, "D"); @@ -261,7 +263,7 @@ TEST(Converter, MoveElemElemMultipleLevels) ASSERT_NE(nullptr, convertedElem); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_FALSE(convertedElem->FirstChildElement("elemD")); } @@ -274,7 +276,7 @@ TEST(Converter, MoveAttrAttrMultipleLevels) std::string xmlString = getXmlString(); // Test moving from attr to attr across multiple levels - TiXmlDocument xmlDoc6; + tinyxml2::XMLDocument xmlDoc6; xmlDoc6.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -283,24 +285,24 @@ TEST(Converter, MoveAttrAttrMultipleLevels) << " " << " " << ""; - TiXmlDocument convertXmlDoc6; + tinyxml2::XMLDocument convertXmlDoc6; convertXmlDoc6.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc6, &convertXmlDoc6); - TiXmlElement *convertedElem = xmlDoc6.FirstChildElement(); + tinyxml2::XMLElement *convertedElem = xmlDoc6.FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + EXPECT_STREQ(convertedElem->Name(), "elemA"); std::string attrValue = convertedElem->Attribute("attrE"); EXPECT_EQ(attrValue, "C"); convertedElem = convertedElem->FirstChildElement("elemB"); ASSERT_NE(nullptr, convertedElem); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_FALSE(convertedElem->Attribute("attrC")); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -312,7 +314,7 @@ TEST(Converter, MoveElemAttrMultipleLevels) std::string xmlString = getXmlString(); // Test moving from elem to attr across multiple levels - TiXmlDocument xmlDoc7; + tinyxml2::XMLDocument xmlDoc7; xmlDoc7.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -321,20 +323,20 @@ TEST(Converter, MoveElemAttrMultipleLevels) << " " << " " << ""; - TiXmlDocument convertXmlDoc7; + tinyxml2::XMLDocument convertXmlDoc7; convertXmlDoc7.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc7, &convertXmlDoc7); - TiXmlElement *convertedElem = xmlDoc7.FirstChildElement(); + tinyxml2::XMLElement *convertedElem = xmlDoc7.FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + EXPECT_STREQ(convertedElem->Name(), "elemA"); std::string attrValue = convertedElem->Attribute("attrE"); EXPECT_EQ(attrValue, "D"); convertedElem = convertedElem->FirstChildElement("elemB"); ASSERT_NE(nullptr, convertedElem); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_FALSE(convertedElem->FirstChildElement("elemD")); } @@ -347,7 +349,7 @@ TEST(Converter, MoveAttrElemMultipleLevels) std::string xmlString = getXmlString(); // Test moving from attr to elem across multiple levels - TiXmlDocument xmlDoc8; + tinyxml2::XMLDocument xmlDoc8; xmlDoc8.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -356,13 +358,13 @@ TEST(Converter, MoveAttrElemMultipleLevels) << " " << " " << ""; - TiXmlDocument convertXmlDoc8; + tinyxml2::XMLDocument convertXmlDoc8; convertXmlDoc8.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc8, &convertXmlDoc8); - TiXmlElement *convertedElem = xmlDoc8.FirstChildElement(); + tinyxml2::XMLElement *convertedElem = xmlDoc8.FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + EXPECT_STREQ(convertedElem->Name(), "elemA"); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemE")); std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); EXPECT_EQ(elemValue, "C"); @@ -370,11 +372,11 @@ TEST(Converter, MoveAttrElemMultipleLevels) ASSERT_NE(nullptr, convertedElem); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_FALSE(convertedElem->Attribute("attrC")); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -386,20 +388,20 @@ TEST(Converter, Add) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test adding element // Set up a convert file @@ -414,15 +416,15 @@ TEST(Converter, Add) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemC")); ASSERT_NE(nullptr, convertedElem->FirstChildElement("elemBB")); std::string elemValue = convertedElem->FirstChildElement("elemBB")->GetText(); @@ -441,7 +443,7 @@ TEST(Converter, AddNoElem) // Set up an xml string for testing std::string xmlString = getXmlString(); - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); // Test adding element @@ -457,23 +459,23 @@ TEST(Converter, AddNoElem) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); // Verify the xml - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -483,7 +485,7 @@ TEST(Converter, AddNoValue) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); // Test adding element @@ -499,22 +501,22 @@ TEST(Converter, AddNoValue) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -526,20 +528,20 @@ TEST(Converter, RemoveElement) std::string xmlString = getRepeatedXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test removing element // Set up a convert file @@ -551,15 +553,15 @@ TEST(Converter, RemoveElement) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemC")); convertedElem = convertedElem->FirstChildElement("elemC"); ASSERT_NE(nullptr, convertedElem); @@ -576,20 +578,20 @@ TEST(Converter, RemoveDescendantElement) std::string xmlString = getRepeatedXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test removing element // Set up a convert file @@ -599,15 +601,16 @@ TEST(Converter, RemoveDescendantElement) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemC")); convertedElem = convertedElem->FirstChildElement("elemC"); ASSERT_NE(nullptr, convertedElem); @@ -642,10 +645,10 @@ TEST(Converter, RemoveDescendantNestedElement) )"; // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertString.c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); @@ -659,15 +662,16 @@ TEST(Converter, RemoveDescendantNestedElement) )"; - TiXmlDocument expectedXmlDoc; + tinyxml2::XMLDocument expectedXmlDoc; expectedXmlDoc.Parse(expectedString.c_str()); - std::stringstream xmlDocOut; - xmlDocOut << xmlDoc; + tinyxml2::XMLPrinter xmlDocOut; + xmlDoc.Print(&xmlDocOut); - std::stringstream expectedXmlDocOut; - expectedXmlDocOut << expectedXmlDoc; - EXPECT_EQ(xmlDocOut.str(), expectedXmlDocOut.str()); + tinyxml2::XMLPrinter expectedXmlDocOut; + expectedXmlDoc.Print(&expectedXmlDocOut); + + EXPECT_STREQ(xmlDocOut.CStr(), expectedXmlDocOut.CStr()); } //////////////////////////////////////////////////// /// Ensure that Converter ignores descendants of or namespaced elements @@ -699,10 +703,10 @@ TEST(Converter, DescendantIgnorePluginOrNamespacedElements) )"; // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertString.c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); @@ -721,15 +725,16 @@ TEST(Converter, DescendantIgnorePluginOrNamespacedElements) )"; - TiXmlDocument expectedXmlDoc; + tinyxml2::XMLDocument expectedXmlDoc; expectedXmlDoc.Parse(expectedString.c_str()); - std::stringstream xmlDocOut; - xmlDocOut << xmlDoc; + tinyxml2::XMLPrinter xmlDocOut; + xmlDoc.Print(&xmlDocOut); + + tinyxml2::XMLPrinter expectedXmlDocOut; + expectedXmlDoc.Print(&expectedXmlDocOut); - std::stringstream expectedXmlDocOut; - expectedXmlDocOut << expectedXmlDoc; - EXPECT_EQ(xmlDocOut.str(), expectedXmlDocOut.str()); + EXPECT_STREQ(xmlDocOut.CStr(), expectedXmlDocOut.CStr()); } //////////////////////////////////////////////////// @@ -741,20 +746,20 @@ TEST(Converter, RemoveElementSubElement) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test adding element // Set up a convert file @@ -764,15 +769,15 @@ TEST(Converter, RemoveElementSubElement) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); ASSERT_TRUE(convertedElem->FirstChildElement("elemC") == nullptr); } @@ -785,20 +790,20 @@ TEST(Converter, RemoveAttr) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test adding element // Set up a convert file @@ -810,15 +815,15 @@ TEST(Converter, RemoveAttr) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); EXPECT_NE(nullptr, convertedElem->FirstChildElement("elemC")); convertedElem = convertedElem->FirstChildElement("elemC"); ASSERT_NE(nullptr, convertedElem); @@ -834,7 +839,7 @@ TEST(Converter, RemoveNoElement) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); // Test adding element @@ -847,22 +852,22 @@ TEST(Converter, RemoveNoElement) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -874,20 +879,20 @@ TEST(Converter, MoveInvalid) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Set up a convert file std::stringstream convertStream; @@ -899,7 +904,7 @@ TEST(Converter, MoveInvalid) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); @@ -907,18 +912,18 @@ TEST(Converter, MoveInvalid) // means that the conversion quietly failed. Make sure the new // document is the same as the original. // Verify the xml - TiXmlElement *convertElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *convertElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemA"); + EXPECT_STREQ(convertElem->Name(), "elemA"); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertElem->Name(), "elemB"); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertElem->Name(), "elemC"); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -930,20 +935,20 @@ TEST(Converter, MoveInvalidPrefix) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Set up a convert file std::stringstream convertStream; @@ -955,7 +960,7 @@ TEST(Converter, MoveInvalidPrefix) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); @@ -963,18 +968,18 @@ TEST(Converter, MoveInvalidPrefix) // means that the conversion quietly failed. Make sure the new // document is the same as the original. // Verify the xml - TiXmlElement *convertElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *convertElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemA"); + EXPECT_STREQ(convertElem->Name(), "elemA"); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertElem->Name(), "elemB"); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertElem->Name(), "elemC"); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -986,20 +991,20 @@ TEST(Converter, CopyElemElem) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test moving from elem to elem // Set up a convert file @@ -1012,22 +1017,22 @@ TEST(Converter, CopyElemElem) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); - TiXmlElement *elemB = convertedElem->FirstChildElement(); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); + tinyxml2::XMLElement *elemB = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, elemB); - EXPECT_EQ(elemB->ValueStr(), "elemB"); - TiXmlElement *elemC = elemB->FirstChild("elemC")->ToElement(); + EXPECT_STREQ(elemB->Name(), "elemB"); + tinyxml2::XMLElement *elemC = elemB->FirstChildElement("elemC"); ASSERT_NE(nullptr, elemC); - TiXmlElement *elemD = elemC->FirstChildElement(); + tinyxml2::XMLElement *elemD = elemC->FirstChildElement(); ASSERT_NE(nullptr, elemD); std::string elemValue = elemD->GetText(); EXPECT_EQ(elemValue, "D"); - TiXmlElement *elemE = elemB->FirstChild("elemE")->ToElement(); + tinyxml2::XMLElement *elemE = elemB->FirstChildElement("elemE"); ASSERT_NE(nullptr, elemE); elemValue = elemE->GetText(); EXPECT_EQ(elemValue, "D"); @@ -1042,20 +1047,20 @@ TEST(Converter, MapInvalid) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Set up an invalid convert file that should do nothing std::stringstream convertStream; @@ -1183,39 +1188,42 @@ TEST(Converter, MapInvalid) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); - std::ostringstream xmlDocBefore; - xmlDocBefore << xmlDoc; + + tinyxml2::XMLPrinter printerBefore; + xmlDoc.Print(&printerBefore); + sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); // Only invalid conversion statements. // Make sure the new document is the same as the original. - std::ostringstream xmlDocAfter; - xmlDocAfter << xmlDoc; - EXPECT_EQ(xmlDocBefore.str(), xmlDocAfter.str()); + tinyxml2::XMLPrinter printerAfter; + xmlDoc.Print(&printerAfter); + + EXPECT_STREQ(printerBefore.CStr(), printerAfter.CStr()); // Verify the xml - TiXmlElement *convertElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *convertElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemA"); + EXPECT_STREQ(convertElem->Name(), "elemA"); ASSERT_NE(nullptr, convertElem->Attribute("attrA")); std::string attrValue = convertElem->Attribute("attrA"); EXPECT_EQ("A", attrValue); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertElem->Name(), "elemB"); ASSERT_NE(nullptr, convertElem->Attribute("attrB")); attrValue = convertElem->Attribute("attrB"); EXPECT_EQ("B", attrValue); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertElem->Name(), "elemC"); ASSERT_NE(nullptr, convertElem->Attribute("attrC")); attrValue = convertElem->Attribute("attrC"); EXPECT_EQ("C", attrValue); convertElem = convertElem->FirstChildElement(); ASSERT_NE(nullptr, convertElem); - EXPECT_EQ(convertElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertElem->Name(), "elemD"); ASSERT_NE(nullptr, convertElem->GetText()); std::string textValue = convertElem->GetText(); EXPECT_EQ("D", textValue); @@ -1230,20 +1238,20 @@ TEST(Converter, MapElemElem) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test moving from elem to elem // Set up a convert file @@ -1294,18 +1302,18 @@ TEST(Converter, MapElemElem) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); ASSERT_NE(nullptr, convertedElem->FirstChildElement("elemD")); std::string elemValue = convertedElem->FirstChildElement("elemD")->GetText(); EXPECT_EQ(elemValue, "D"); @@ -1330,7 +1338,7 @@ TEST(Converter, MapElemAttr) std::string xmlString = getXmlString(); // Test moving from elem to attr - TiXmlDocument xmlDoc2; + tinyxml2::XMLDocument xmlDoc2; xmlDoc2.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1345,22 +1353,22 @@ TEST(Converter, MapElemAttr) << " " << " " << ""; - TiXmlDocument convertXmlDoc2; + tinyxml2::XMLDocument convertXmlDoc2; convertXmlDoc2.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc2, &convertXmlDoc2); - TiXmlElement *convertedElem = xmlDoc2.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc2.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); // check for new attribute ASSERT_NE(nullptr, convertedElem->Attribute("attrE")); std::string attrValue = convertedElem->Attribute("attrE"); EXPECT_EQ(attrValue, "E"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_TRUE(convertedElem->FirstChildElement("elemD")); } @@ -1373,7 +1381,7 @@ TEST(Converter, MapAttrAttr) std::string xmlString = getXmlString(); // Test moving from attr to attr - TiXmlDocument xmlDoc3; + tinyxml2::XMLDocument xmlDoc3; xmlDoc3.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1388,15 +1396,15 @@ TEST(Converter, MapAttrAttr) << " " << " " << ""; - TiXmlDocument convertXmlDoc3; + tinyxml2::XMLDocument convertXmlDoc3; convertXmlDoc3.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc3, &convertXmlDoc3); - TiXmlElement *convertedElem = xmlDoc3.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc3.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); // check for new attribute ASSERT_NE(nullptr, convertedElem->Attribute("attrE")); std::string attrValue = convertedElem->Attribute("attrE"); @@ -1407,11 +1415,11 @@ TEST(Converter, MapAttrAttr) EXPECT_EQ(attrValue, "B"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_TRUE(convertedElem->Attribute("attrC")); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -1423,7 +1431,7 @@ TEST(Converter, MapAttrElem) std::string xmlString = getXmlString(); // Test moving from attr to elem - TiXmlDocument xmlDoc4; + tinyxml2::XMLDocument xmlDoc4; xmlDoc4.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1438,15 +1446,15 @@ TEST(Converter, MapAttrElem) << " " << " " << ""; - TiXmlDocument convertXmlDoc4; + tinyxml2::XMLDocument convertXmlDoc4; convertXmlDoc4.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc4, &convertXmlDoc4); - TiXmlElement *convertedElem = xmlDoc4.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc4.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); ASSERT_NE(nullptr, convertedElem->FirstChildElement("elemE")); std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); EXPECT_EQ(elemValue, "E"); @@ -1460,7 +1468,7 @@ TEST(Converter, MapAttrElem) EXPECT_TRUE(convertedElem->Attribute("attrC")); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -1472,7 +1480,7 @@ TEST(Converter, MapElemElemMultipleLevels) std::string xmlString = getXmlString(); // Test moving from elem to elem across multiple levels - TiXmlDocument xmlDoc5; + tinyxml2::XMLDocument xmlDoc5; xmlDoc5.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1485,13 +1493,14 @@ TEST(Converter, MapElemElemMultipleLevels) << " " << " " << ""; - TiXmlDocument convertXmlDoc5; + tinyxml2::XMLDocument convertXmlDoc5; convertXmlDoc5.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc5, &convertXmlDoc5); - TiXmlElement *convertedElem = xmlDoc5.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); - TiXmlElement *convertedElem2 = convertedElem->FirstChildElement("elemCC"); + tinyxml2::XMLElement *convertedElem = xmlDoc5.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); + tinyxml2::XMLElement *convertedElem2 = + convertedElem->FirstChildElement("elemCC"); ASSERT_NE(nullptr, convertedElem2); convertedElem2 = convertedElem2->FirstChildElement("elemDD"); ASSERT_NE(nullptr, convertedElem2); @@ -1502,7 +1511,7 @@ TEST(Converter, MapElemElemMultipleLevels) ASSERT_NE(nullptr, convertedElem); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_TRUE(convertedElem->FirstChildElement("elemD")); } @@ -1515,7 +1524,7 @@ TEST(Converter, MapAttrAttrMultipleLevels) std::string xmlString = getXmlString(); // Test moving from attr to attr across multiple levels - TiXmlDocument xmlDoc6; + tinyxml2::XMLDocument xmlDoc6; xmlDoc6.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1528,14 +1537,15 @@ TEST(Converter, MapAttrAttrMultipleLevels) << " " << " " << ""; - TiXmlDocument convertXmlDoc6; + tinyxml2::XMLDocument convertXmlDoc6; convertXmlDoc6.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc6, &convertXmlDoc6); - TiXmlElement *convertedElem = xmlDoc6.FirstChildElement(); + tinyxml2::XMLElement *convertedElem = xmlDoc6.FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); - TiXmlElement *convertedElem2 = convertedElem->FirstChildElement("elemCC"); + EXPECT_STREQ(convertedElem->Name(), "elemA"); + tinyxml2::XMLElement *convertedElem2 = + convertedElem->FirstChildElement("elemCC"); ASSERT_NE(nullptr, convertedElem2); convertedElem2 = convertedElem2->FirstChildElement("elemDD"); ASSERT_NE(nullptr, convertedElem2); @@ -1545,11 +1555,11 @@ TEST(Converter, MapAttrAttrMultipleLevels) ASSERT_NE(nullptr, convertedElem); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_TRUE(convertedElem->Attribute("attrC")); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -1561,7 +1571,7 @@ TEST(Converter, MapElemAttrMultipleLevels) std::string xmlString = getXmlString(); // Test moving from elem to attr across multiple levels - TiXmlDocument xmlDoc7; + tinyxml2::XMLDocument xmlDoc7; xmlDoc7.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1574,14 +1584,15 @@ TEST(Converter, MapElemAttrMultipleLevels) << " " << " " << ""; - TiXmlDocument convertXmlDoc7; + tinyxml2::XMLDocument convertXmlDoc7; convertXmlDoc7.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc7, &convertXmlDoc7); - TiXmlElement *convertedElem = xmlDoc7.FirstChildElement(); + tinyxml2::XMLElement *convertedElem = xmlDoc7.FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); - TiXmlElement *convertedElem2 = convertedElem->FirstChildElement("elemCC"); + EXPECT_STREQ(convertedElem->Name(), "elemA"); + tinyxml2::XMLElement *convertedElem2 = + convertedElem->FirstChildElement("elemCC"); ASSERT_NE(nullptr, convertedElem2); convertedElem2 = convertedElem2->FirstChildElement("elemDD"); ASSERT_NE(nullptr, convertedElem2); @@ -1591,7 +1602,7 @@ TEST(Converter, MapElemAttrMultipleLevels) ASSERT_NE(nullptr, convertedElem); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_TRUE(convertedElem->FirstChildElement("elemD")); } @@ -1604,7 +1615,7 @@ TEST(Converter, MapAttrElemMultipleLevels) std::string xmlString = getXmlString(); // Test moving from attr to elem across multiple levels - TiXmlDocument xmlDoc8; + tinyxml2::XMLDocument xmlDoc8; xmlDoc8.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1617,14 +1628,15 @@ TEST(Converter, MapAttrElemMultipleLevels) << " " << " " << ""; - TiXmlDocument convertXmlDoc8; + tinyxml2::XMLDocument convertXmlDoc8; convertXmlDoc8.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc8, &convertXmlDoc8); - TiXmlElement *convertedElem = xmlDoc8.FirstChildElement(); + tinyxml2::XMLElement *convertedElem = xmlDoc8.FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); - TiXmlElement *convertedElem2 = convertedElem->FirstChildElement("elemCC"); + EXPECT_STREQ(convertedElem->Name(), "elemA"); + tinyxml2::XMLElement *convertedElem2 = + convertedElem->FirstChildElement("elemCC"); ASSERT_NE(nullptr, convertedElem2); convertedElem2 = convertedElem2->FirstChildElement("elemDD"); ASSERT_NE(nullptr, convertedElem2); @@ -1635,11 +1647,11 @@ TEST(Converter, MapAttrElemMultipleLevels) ASSERT_NE(nullptr, convertedElem); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); EXPECT_TRUE(convertedElem->Attribute("attrC")); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -1649,20 +1661,20 @@ TEST(Converter, RenameElemElem) std::string xmlString = getXmlString(); // Verify the xml - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - TiXmlElement *childElem = xmlDoc.FirstChildElement(); + tinyxml2::XMLElement *childElem = xmlDoc.FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemA"); + EXPECT_STREQ(childElem->Name(), "elemA"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemB"); + EXPECT_STREQ(childElem->Name(), "elemB"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemC"); + EXPECT_STREQ(childElem->Name(), "elemC"); childElem = childElem->FirstChildElement(); ASSERT_NE(nullptr, childElem); - EXPECT_EQ(childElem->ValueStr(), "elemD"); + EXPECT_STREQ(childElem->Name(), "elemD"); // Test moving from elem to elem // Set up a convert file @@ -1677,20 +1689,20 @@ TEST(Converter, RenameElemElem) << " " << " " << ""; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument convertXmlDoc; convertXmlDoc.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); - TiXmlElement *elemB = convertedElem->FirstChildElement(); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); + tinyxml2::XMLElement *elemB = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, elemB); - EXPECT_EQ(elemB->ValueStr(), "elemB"); - TiXmlElement *elemC = elemB->FirstChild("elemC")->ToElement(); + EXPECT_STREQ(elemB->Name(), "elemB"); + tinyxml2::XMLElement *elemC = elemB->FirstChildElement("elemC"); ASSERT_NE(nullptr, elemC); - TiXmlElement *elemE = elemC->FirstChildElement(); + tinyxml2::XMLElement *elemE = elemC->FirstChildElement(); ASSERT_NE(nullptr, elemE); - EXPECT_EQ(elemE->ValueStr(), "elemE"); + EXPECT_STREQ(elemE->Name(), "elemE"); std::string elemValue = elemE->GetText(); ASSERT_EQ(elemValue, "D"); } @@ -1702,7 +1714,7 @@ TEST(Converter, RenameAttrAttr) std::string xmlString = getXmlString(); // Test moving from attr to attr - TiXmlDocument xmlDoc3; + tinyxml2::XMLDocument xmlDoc3; xmlDoc3.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1715,19 +1727,19 @@ TEST(Converter, RenameAttrAttr) << " " << " " << ""; - TiXmlDocument convertXmlDoc3; + tinyxml2::XMLDocument convertXmlDoc3; convertXmlDoc3.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc3, &convertXmlDoc3); - TiXmlElement *convertedElem = xmlDoc3.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc3.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); - convertedElem = convertedElem->FirstChild("elemE")->ToElement(); + EXPECT_STREQ(convertedElem->Name(), "elemC"); + convertedElem = convertedElem->FirstChildElement("elemE"); std::string attrValue = convertedElem->Attribute("attrE"); EXPECT_EQ(attrValue, "C"); } @@ -1739,7 +1751,7 @@ TEST(Converter, RenameNoFrom) std::string xmlString = getXmlString(); // Test failing to move since there is nothing specified in the "from" element - TiXmlDocument xmlDoc3; + tinyxml2::XMLDocument xmlDoc3; xmlDoc3.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1752,21 +1764,21 @@ TEST(Converter, RenameNoFrom) << " " << " " << ""; - TiXmlDocument convertXmlDoc3; + tinyxml2::XMLDocument convertXmlDoc3; convertXmlDoc3.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc3, &convertXmlDoc3); - TiXmlElement *convertedElem = xmlDoc3.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc3.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -1776,7 +1788,7 @@ TEST(Converter, RenameNoTo) std::string xmlString = getXmlString(); // Test failing to move since there is nothing specified in the "to" element - TiXmlDocument xmlDoc3; + tinyxml2::XMLDocument xmlDoc3; xmlDoc3.Parse(xmlString.c_str()); std::stringstream convertStream; convertStream << "" @@ -1789,21 +1801,21 @@ TEST(Converter, RenameNoTo) << " " << " " << ""; - TiXmlDocument convertXmlDoc3; + tinyxml2::XMLDocument convertXmlDoc3; convertXmlDoc3.Parse(convertStream.str().c_str()); sdf::Converter::Convert(&xmlDoc3, &convertXmlDoc3); - TiXmlElement *convertedElem = xmlDoc3.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + tinyxml2::XMLElement *convertedElem = xmlDoc3.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "elemA"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_STREQ(convertedElem->Name(), "elemB"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_STREQ(convertedElem->Name(), "elemC"); convertedElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, convertedElem); - EXPECT_EQ(convertedElem->ValueStr(), "elemD"); + EXPECT_STREQ(convertedElem->Name(), "elemD"); } //////////////////////////////////////////////////// @@ -1814,7 +1826,7 @@ TEST(Converter, GazeboToSDF) << ""; std::string xmlString = stream.str(); - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); EXPECT_FALSE(sdf::Converter::Convert(&xmlDoc, "1.3")); } @@ -1822,8 +1834,8 @@ TEST(Converter, GazeboToSDF) //////////////////////////////////////////////////// TEST(Converter, NullDoc) { - TiXmlDocument xmlDoc; - TiXmlDocument convertXmlDoc; + tinyxml2::XMLDocument xmlDoc; + tinyxml2::XMLDocument convertXmlDoc; ASSERT_THROW(sdf::Converter::Convert(nullptr, &convertXmlDoc), sdf::AssertionInternalError); @@ -1838,7 +1850,7 @@ TEST(Converter, NoVersion) { std::string xmlString(""); - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); ASSERT_FALSE(sdf::Converter::Convert(&xmlDoc, "1.3")); @@ -1849,18 +1861,19 @@ TEST(Converter, SameVersion) { std::string xmlString(""); - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); - std::ostringstream xmlDocBefore; - xmlDocBefore << xmlDoc; + tinyxml2::XMLPrinter printerBefore; + xmlDoc.Print(&printerBefore); ASSERT_TRUE(sdf::Converter::Convert(&xmlDoc, "1.3")); - std::ostringstream xmlDocAfter; - xmlDocAfter << xmlDoc; + + tinyxml2::XMLPrinter printerAfter; + xmlDoc.Print(&printerAfter); // Expect xmlDoc to be unchanged after conversion - EXPECT_EQ(xmlDocBefore.str(), xmlDocAfter.str()); + EXPECT_STREQ(printerBefore.CStr(), printerAfter.CStr()); } //////////////////////////////////////////////////// @@ -1868,7 +1881,7 @@ TEST(Converter, NewerVersion) { std::string xmlString(""); - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); ASSERT_TRUE(sdf::Converter::Convert(&xmlDoc, "1.6")); @@ -1879,7 +1892,7 @@ TEST(Converter, MuchNewerVersion) { std::string xmlString(""); - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); ASSERT_TRUE(sdf::Converter::Convert(&xmlDoc, "1.6")); @@ -1925,42 +1938,42 @@ TEST(Converter, IMU_15_to_16) )"; - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); // Convert - TiXmlDocument convertXmlDoc; - convertXmlDoc.LoadFile(CONVERT_DOC_15_16); + tinyxml2::XMLDocument convertXmlDoc; + convertXmlDoc.LoadFile(CONVERT_DOC_15_16.c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); // Check some basic elements - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "sdf"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "sdf"); convertedElem = convertedElem->FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "world"); + EXPECT_STREQ(convertedElem->Name(), "world"); convertedElem = convertedElem->FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "model"); + EXPECT_STREQ(convertedElem->Name(), "model"); convertedElem = convertedElem->FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "link"); + EXPECT_STREQ(convertedElem->Name(), "link"); convertedElem = convertedElem->FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "sensor"); + EXPECT_STREQ(convertedElem->Name(), "sensor"); // Get the imu - TiXmlElement *imuElem = convertedElem->FirstChildElement(); - EXPECT_EQ(imuElem->ValueStr(), "imu"); + tinyxml2::XMLElement *imuElem = convertedElem->FirstChildElement(); + EXPECT_STREQ(imuElem->Name(), "imu"); // Get the angular_velocity - TiXmlElement *angVelElem = imuElem->FirstChildElement(); - EXPECT_EQ(angVelElem->ValueStr(), "angular_velocity"); + tinyxml2::XMLElement *angVelElem = imuElem->FirstChildElement(); + EXPECT_STREQ(angVelElem->Name(), "angular_velocity"); // Get the linear_acceleration - TiXmlElement *linAccElem = angVelElem->NextSiblingElement(); - EXPECT_EQ(linAccElem->ValueStr(), "linear_acceleration"); + tinyxml2::XMLElement *linAccElem = angVelElem->NextSiblingElement(); + EXPECT_STREQ(linAccElem->Name(), "linear_acceleration"); std::array axis = {'x', 'y', 'z'}; - TiXmlElement *angVelAxisElem = angVelElem->FirstChildElement(); - TiXmlElement *linAccAxisElem = linAccElem->FirstChildElement(); + tinyxml2::XMLElement *angVelAxisElem = angVelElem->FirstChildElement(); + tinyxml2::XMLElement *linAccAxisElem = linAccElem->FirstChildElement(); // Iterate over , , and elements under and // @@ -1969,11 +1982,11 @@ TEST(Converter, IMU_15_to_16) EXPECT_EQ(angVelAxisElem->Value()[0], a); EXPECT_EQ(linAccAxisElem->Value()[0], a); - TiXmlElement *angVelAxisNoiseElem = angVelAxisElem->FirstChildElement(); - TiXmlElement *linAccAxisNoiseElem = linAccAxisElem->FirstChildElement(); + auto *angVelAxisNoiseElem = angVelAxisElem->FirstChildElement(); + auto *linAccAxisNoiseElem = linAccAxisElem->FirstChildElement(); - EXPECT_EQ(angVelAxisNoiseElem->ValueStr(), "noise"); - EXPECT_EQ(linAccAxisNoiseElem->ValueStr(), "noise"); + EXPECT_STREQ(angVelAxisNoiseElem->Name(), "noise"); + EXPECT_STREQ(linAccAxisNoiseElem->Name(), "noise"); EXPECT_STREQ(angVelAxisNoiseElem->Attribute("type"), "gaussian"); EXPECT_STREQ(linAccAxisNoiseElem->Attribute("type"), "gaussian"); @@ -2019,33 +2032,33 @@ TEST(Converter, World_15_to_16) )"; - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); // Convert - TiXmlDocument convertXmlDoc; - convertXmlDoc.LoadFile(CONVERT_DOC_15_16); + tinyxml2::XMLDocument convertXmlDoc; + convertXmlDoc.LoadFile(CONVERT_DOC_15_16.c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); // Check some basic elements - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "sdf"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "sdf"); convertedElem = convertedElem->FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "world"); + EXPECT_STREQ(convertedElem->Name(), "world"); convertedElem = convertedElem->FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "physics"); + EXPECT_STREQ(convertedElem->Name(), "physics"); // gravity and magnetic_field should have been moved from physics to world EXPECT_EQ(nullptr, convertedElem->FirstChildElement("gravity")); EXPECT_EQ(nullptr, convertedElem->FirstChildElement("magnetic_field")); // Get the gravity - TiXmlElement *gravityElem = convertedElem->NextSiblingElement("gravity"); + auto *gravityElem = convertedElem->NextSiblingElement("gravity"); ASSERT_NE(nullptr, gravityElem); EXPECT_STREQ(gravityElem->GetText(), "1 0 -9.8"); // Get the magnetic_field - TiXmlElement *magneticFieldElem = + tinyxml2::XMLElement *magneticFieldElem = convertedElem->NextSiblingElement("magnetic_field"); ASSERT_NE(nullptr, magneticFieldElem); EXPECT_STREQ(magneticFieldElem->GetText(), "1 2 3"); @@ -2075,52 +2088,53 @@ TEST(Converter, Pose_16_to_17) )"; - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmlString.c_str()); // Convert - TiXmlDocument convertXmlDoc; - convertXmlDoc.LoadFile(CONVERT_DOC_16_17); + tinyxml2::XMLDocument convertXmlDoc; + convertXmlDoc.LoadFile(CONVERT_DOC_16_17.c_str()); sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); // Check some basic elements - TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "sdf"); + tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_STREQ(convertedElem->Name(), "sdf"); convertedElem = convertedElem->FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "world"); + EXPECT_STREQ(convertedElem->Name(), "world"); convertedElem = convertedElem->FirstChildElement(); - EXPECT_EQ(convertedElem->ValueStr(), "model"); + EXPECT_STREQ(convertedElem->Name(), "model"); - TiXmlElement *modelPoseElem = convertedElem->FirstChildElement(); + tinyxml2::XMLElement *modelPoseElem = convertedElem->FirstChildElement(); ASSERT_NE(nullptr, modelPoseElem); - EXPECT_EQ("pose", modelPoseElem->ValueStr()); + EXPECT_STREQ("pose", modelPoseElem->Name()); // frame attribute should have been moved to relative_to EXPECT_EQ(nullptr, modelPoseElem->Attribute("frame")); EXPECT_NE(nullptr, modelPoseElem->Attribute("relative_to")); EXPECT_STREQ("world", modelPoseElem->Attribute("relative_to")); - TiXmlElement *parentLinkElem = modelPoseElem->NextSiblingElement(); + tinyxml2::XMLElement *parentLinkElem = modelPoseElem->NextSiblingElement(); ASSERT_NE(nullptr, parentLinkElem); - EXPECT_EQ("link", parentLinkElem->ValueStr()); + EXPECT_STREQ("link", parentLinkElem->Name()); EXPECT_EQ(nullptr, parentLinkElem->FirstChildElement()); - TiXmlElement *childLinkElem = parentLinkElem->NextSiblingElement(); + tinyxml2::XMLElement *childLinkElem = parentLinkElem->NextSiblingElement(); ASSERT_NE(nullptr, childLinkElem); - EXPECT_EQ("link", childLinkElem->ValueStr()); - TiXmlElement *childLinkPoseElem = childLinkElem->FirstChildElement(); + EXPECT_STREQ("link", childLinkElem->Name()); + tinyxml2::XMLElement *childLinkPoseElem = childLinkElem->FirstChildElement(); ASSERT_NE(nullptr, childLinkPoseElem); - EXPECT_EQ("pose", childLinkPoseElem->ValueStr()); + EXPECT_STREQ("pose", childLinkPoseElem->Name()); // frame attribute should have been moved to relative_to EXPECT_EQ(nullptr, childLinkPoseElem->Attribute("frame")); EXPECT_NE(nullptr, childLinkPoseElem->Attribute("relative_to")); EXPECT_STREQ("joint", childLinkPoseElem->Attribute("relative_to")); - TiXmlElement *jointLinkElem = childLinkElem->NextSiblingElement(); + tinyxml2::XMLElement *jointLinkElem = childLinkElem->NextSiblingElement(); ASSERT_NE(nullptr, jointLinkElem); - EXPECT_EQ("joint", jointLinkElem->ValueStr()); - TiXmlElement *jointLinkPoseElem = jointLinkElem->FirstChildElement("pose"); + EXPECT_STREQ("joint", jointLinkElem->Name()); + tinyxml2::XMLElement *jointLinkPoseElem = + jointLinkElem->FirstChildElement("pose"); ASSERT_NE(nullptr, jointLinkPoseElem); - EXPECT_EQ("pose", jointLinkPoseElem->ValueStr()); + EXPECT_STREQ("pose", jointLinkPoseElem->Name()); // frame attribute should have been moved to relative_to EXPECT_EQ(nullptr, jointLinkPoseElem->Attribute("frame")); EXPECT_NE(nullptr, jointLinkPoseElem->Attribute("relative_to")); diff --git a/src/SDFExtension.hh b/src/SDFExtension.hh index 4c5ce3381..53ca1df83 100644 --- a/src/SDFExtension.hh +++ b/src/SDFExtension.hh @@ -18,7 +18,7 @@ #ifndef SDFORMAT_SDFEXTENSION_HH_ #define SDFORMAT_SDFEXTENSION_HH_ -#include +#include #include #include @@ -34,6 +34,8 @@ namespace sdf // Inline bracket to help doxygen filtering. inline namespace SDF_VERSION_NAMESPACE { // + using XMLDocumentPtr= std::shared_ptr; + using XMLElementPtr = std::shared_ptr; /// \internal /// \brief A class for holding sdf extension elements in urdf @@ -57,7 +59,7 @@ namespace sdf public: std::string material; /// \brief blobs of xml to be copied into the visual sdf element - public: std::vector > visual_blobs; + public: std::vector visual_blobs; /// \brief blobs of xml to be copied into the collision sdf element /// An example might be: @@ -84,7 +86,7 @@ namespace sdf /// /// where all the contents of `` element is copied into the /// resulting collision sdf. - public: std::vector > collision_blobs; + public: std::vector collision_blobs; // body, default off public: bool setStaticFlag; @@ -118,7 +120,7 @@ namespace sdf public: bool implicitSpringDamper; // blobs into body or robot - public: std::vector > blobs; + public: std::vector blobs; friend class URDF2SDF; }; diff --git a/src/Types.cc b/src/Types.cc index a0cd1636e..13df3060c 100644 --- a/src/Types.cc +++ b/src/Types.cc @@ -59,13 +59,13 @@ std::string trim(const char *_in) ////////////////////////////////////////////////// std::string trim(const std::string &_in) { - const size_t strBegin = _in.find_first_not_of(" \t"); + const size_t strBegin = _in.find_first_not_of(" \t\n"); if (strBegin == std::string::npos) { return ""; } - const size_t strRange = _in.find_last_not_of(" \t") - strBegin + 1; + const size_t strRange = _in.find_last_not_of(" \t\n") - strBegin + 1; return _in.substr(strBegin, strRange); } diff --git a/src/Types_TEST.cc b/src/Types_TEST.cc index 73775cd8f..1a406970e 100644 --- a/src/Types_TEST.cc +++ b/src/Types_TEST.cc @@ -94,6 +94,9 @@ TEST(Types, trim_nothing) out = sdf::trim("\txyz\t"); EXPECT_EQ(out, "xyz"); + + out = sdf::trim("\n xyz \n"); + EXPECT_EQ(out, "xyz"); } ///////////////////////////////////////////////// diff --git a/src/XmlUtils.cc b/src/XmlUtils.cc new file mode 100644 index 000000000..ff2d86b93 --- /dev/null +++ b/src/XmlUtils.cc @@ -0,0 +1,60 @@ +/* + * Copyright 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#include + +#include "XmlUtils.hh" + +#include "sdf/Console.hh" + +namespace sdf +{ +inline namespace SDF_VERSION_NAMESPACE { + +///////////////////////////////////////////////// +tinyxml2::XMLNode *DeepClone(tinyxml2::XMLDocument *_doc, + const tinyxml2::XMLNode *_src) +{ + if (_src == nullptr) + { + sdferr << "Pointer to XML node _src is NULL\n"; + return nullptr; + } + + tinyxml2::XMLNode *copy = _src->ShallowClone(_doc); + if (copy == nullptr) + { + sdferr << "Failed to clone node " << _src->Value() << "\n"; + return nullptr; + } + + for (const tinyxml2::XMLNode *node = _src->FirstChild(); node != nullptr; + node = node->NextSibling()) + { + auto *childCopy = DeepClone(_doc, node); + if (childCopy == nullptr) + { + sdferr << "Failed to clone child " << node->Value() << "\n"; + return nullptr; + } + copy->InsertEndChild(childCopy); + } + + return copy; +} +} +} // namespace sdf + diff --git a/src/XmlUtils.hh b/src/XmlUtils.hh new file mode 100644 index 000000000..82b08b2b9 --- /dev/null +++ b/src/XmlUtils.hh @@ -0,0 +1,45 @@ +/* + * Copyright 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef SDFORMAT_XMLUTILS_HH +#define SDFORMAT_XMLUTILS_HH + +#include +#include + +#include "sdf/Error.hh" +#include "sdf/Element.hh" +#include "sdf/Types.hh" + +namespace sdf +{ + // Inline bracket to help doxygen filtering. + inline namespace SDF_VERSION_NAMESPACE { + + /// \brief Perform a deep copy of an XML Node + /// + /// This copies an XMLNode _src and all of its decendants + /// into a specified XMLDocument. + /// + /// \param[in] _doc Document in which to place the copied node + /// \param[in] _src The node to deep copy + /// \returns The newly copied node upon success OR + /// nullptr if an error occurs. + tinyxml2::XMLNode *DeepClone(tinyxml2::XMLDocument *_doc, + const tinyxml2::XMLNode *_src); + } +} +#endif diff --git a/src/XmlUtils_TEST.cc b/src/XmlUtils_TEST.cc new file mode 100644 index 000000000..aef79262d --- /dev/null +++ b/src/XmlUtils_TEST.cc @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include + +#include "XmlUtils.hh" + +///////////////////////////////////////////////// +TEST(XMLUtils, DeepClone) +{ + tinyxml2::XMLDocument oldDoc; + tinyxml2::XMLDocument newDoc; + + std::string docXml = R"( + + Hello World + + )"; + + auto ret = oldDoc.Parse(docXml.c_str()); + ASSERT_EQ(tinyxml2::XML_SUCCESS, ret); + + auto root = oldDoc.FirstChild(); + auto newRoot = sdf::DeepClone(&newDoc, root); + + EXPECT_STREQ("document", newRoot->ToElement()->Name()); + + auto newChild = newRoot->FirstChild(); + EXPECT_STREQ("nodeA", newChild->ToElement()->Name()); + + auto newChildB = newChild->FirstChild(); + EXPECT_STREQ("nodeB", newChildB->ToElement()->Name()); + + auto childB_attr = newChildB->ToElement()->Attribute("attr"); + EXPECT_STREQ("true", childB_attr); + + auto childB_text = newChildB->ToElement()->GetText(); + EXPECT_STREQ("Hello World", childB_text); +} diff --git a/src/parser.cc b/src/parser.cc index 309aa831a..12fbed333 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -82,24 +82,22 @@ bool readStringInternal( template static inline bool _initFile(const std::string &_filename, TPtr _sdf) { - TiXmlDocument xmlDoc; - if (xmlDoc.LoadFile(_filename)) + tinyxml2::XMLDocument xmlDoc; + if (tinyxml2::XML_SUCCESS != xmlDoc.LoadFile(_filename.c_str())) { - return initDoc(&xmlDoc, _sdf); - } - else - { - sdferr << "Unable to load file[" << _filename << "]\n"; + sdferr << "Unable to load file[" + << _filename << "]: " << xmlDoc.ErrorStr() << "\n"; + return false; } - return false; + return initDoc(&xmlDoc, _sdf); } ////////////////////////////////////////////////// bool init(SDFPtr _sdf) { std::string xmldata = SDF::EmbeddedSpec("root.sdf", false); - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmldata.c_str()); return initDoc(&xmlDoc, _sdf); } @@ -110,7 +108,7 @@ bool initFile(const std::string &_filename, SDFPtr _sdf) std::string xmldata = SDF::EmbeddedSpec(_filename, true); if (!xmldata.empty()) { - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmldata.c_str()); return initDoc(&xmlDoc, _sdf); } @@ -123,7 +121,7 @@ bool initFile(const std::string &_filename, ElementPtr _sdf) std::string xmldata = SDF::EmbeddedSpec(_filename, true); if (!xmldata.empty()) { - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(xmldata.c_str()); return initDoc(&xmlDoc, _sdf); } @@ -133,11 +131,10 @@ bool initFile(const std::string &_filename, ElementPtr _sdf) ////////////////////////////////////////////////// bool initString(const std::string &_xmlString, SDFPtr _sdf) { - TiXmlDocument xmlDoc; - xmlDoc.Parse(_xmlString.c_str()); - if (xmlDoc.Error()) + tinyxml2::XMLDocument xmlDoc; + if (xmlDoc.Parse(_xmlString.c_str())) { - sdferr << "Failed to parse string as XML: " << xmlDoc.ErrorDesc() << '\n'; + sdferr << "Failed to parse string as XML: " << xmlDoc.ErrorStr() << '\n'; return false; } @@ -145,7 +142,7 @@ bool initString(const std::string &_xmlString, SDFPtr _sdf) } ////////////////////////////////////////////////// -inline TiXmlElement *_initDocGetElement(TiXmlDocument *_xmlDoc) +inline tinyxml2::XMLElement *_initDocGetElement(tinyxml2::XMLDocument *_xmlDoc) { if (!_xmlDoc) { @@ -153,7 +150,7 @@ inline TiXmlElement *_initDocGetElement(TiXmlDocument *_xmlDoc) return nullptr; } - TiXmlElement *element = _xmlDoc->FirstChildElement("element"); + tinyxml2::XMLElement *element = _xmlDoc->FirstChildElement("element"); if (!element) { sdferr << "Could not find the 'element' element in the xml file\n"; @@ -164,7 +161,7 @@ inline TiXmlElement *_initDocGetElement(TiXmlDocument *_xmlDoc) } ////////////////////////////////////////////////// -bool initDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf) +bool initDoc(tinyxml2::XMLDocument *_xmlDoc, SDFPtr _sdf) { auto element = _initDocGetElement(_xmlDoc); if (!element) @@ -176,7 +173,7 @@ bool initDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf) } ////////////////////////////////////////////////// -bool initDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf) +bool initDoc(tinyxml2::XMLDocument *_xmlDoc, ElementPtr _sdf) { auto element = _initDocGetElement(_xmlDoc); if (!element) @@ -188,7 +185,7 @@ bool initDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf) } ////////////////////////////////////////////////// -bool initXml(TiXmlElement *_xml, ElementPtr _sdf) +bool initXml(tinyxml2::XMLElement *_xml, ElementPtr _sdf) { const char *refString = _xml->Attribute("ref"); if (refString) @@ -218,7 +215,7 @@ bool initXml(TiXmlElement *_xml, ElementPtr _sdf) bool required = std::string(requiredString) == "1" ? true : false; const char *elemDefaultValue = _xml->Attribute("default"); std::string description; - TiXmlElement *descChild = _xml->FirstChildElement("description"); + tinyxml2::XMLElement *descChild = _xml->FirstChildElement("description"); if (descChild && descChild->GetText()) { description = descChild->GetText(); @@ -243,10 +240,10 @@ bool initXml(TiXmlElement *_xml, ElementPtr _sdf) } // Get all attributes - for (TiXmlElement *child = _xml->FirstChildElement("attribute"); + for (tinyxml2::XMLElement *child = _xml->FirstChildElement("attribute"); child; child = child->NextSiblingElement("attribute")) { - TiXmlElement *descriptionChild = child->FirstChildElement("description"); + auto *descriptionChild = child->FirstChildElement("description"); const char *name = child->Attribute("name"); const char *type = child->Attribute("type"); const char *defaultValue = child->Attribute("default"); @@ -286,14 +283,14 @@ bool initXml(TiXmlElement *_xml, ElementPtr _sdf) } // Read the element description - TiXmlElement *descChild = _xml->FirstChildElement("description"); + tinyxml2::XMLElement *descChild = _xml->FirstChildElement("description"); if (descChild && descChild->GetText()) { _sdf->SetDescription(descChild->GetText()); } // Get all child elements - for (TiXmlElement *child = _xml->FirstChildElement("element"); + for (tinyxml2::XMLElement *child = _xml->FirstChildElement("element"); child; child = child->NextSiblingElement("element")) { const char *copyDataString = child->Attribute("copy_data"); @@ -312,7 +309,7 @@ bool initXml(TiXmlElement *_xml, ElementPtr _sdf) } // Get all include elements - for (TiXmlElement *child = _xml->FirstChildElement("include"); + for (tinyxml2::XMLElement *child = _xml->FirstChildElement("include"); child; child = child->NextSiblingElement("include")) { std::string filename = child->Attribute("filename"); @@ -322,7 +319,7 @@ bool initXml(TiXmlElement *_xml, ElementPtr _sdf) initFile(filename, element); // override description for include elements - TiXmlElement *description = child->FirstChildElement("description"); + tinyxml2::XMLElement *description = child->FirstChildElement("description"); if (description) { element->SetDescription(description->GetText()); @@ -393,7 +390,7 @@ bool readFileWithoutConversion( bool readFileInternal(const std::string &_filename, SDFPtr _sdf, const bool _convert, Errors &_errors) { - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; std::string filename = sdf::findFile(_filename, true, true); if (filename.empty()) @@ -413,10 +410,11 @@ bool readFileInternal(const std::string &_filename, SDFPtr _sdf, return false; } - if (!xmlDoc.LoadFile(filename)) + auto error_code = xmlDoc.LoadFile(filename.c_str()); + if (error_code) { sdferr << "Error parsing XML in file [" << filename << "]: " - << xmlDoc.ErrorDesc() << '\n'; + << xmlDoc.ErrorStr() << '\n'; return false; } @@ -428,7 +426,8 @@ bool readFileInternal(const std::string &_filename, SDFPtr _sdf, else if (URDF2SDF::IsURDF(filename)) { URDF2SDF u2g; - TiXmlDocument doc = u2g.InitModelFile(filename); + tinyxml2::XMLDocument doc; + u2g.InitModelFile(filename, &doc); if (sdf::readDoc(&doc, _sdf, "urdf file", _convert, _errors)) { sdfdbg << "parse from urdf file [" << _filename << "].\n"; @@ -474,11 +473,11 @@ bool readStringWithoutConversion( bool readStringInternal(const std::string &_xmlString, SDFPtr _sdf, const bool _convert, Errors &_errors) { - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(_xmlString.c_str()); if (xmlDoc.Error()) { - sdferr << "Error parsing XML from string: " << xmlDoc.ErrorDesc() << '\n'; + sdferr << "Error parsing XML from string: " << xmlDoc.ErrorStr() << '\n'; return false; } if (readDoc(&xmlDoc, _sdf, "data-string", _convert, _errors)) @@ -488,7 +487,9 @@ bool readStringInternal(const std::string &_xmlString, SDFPtr _sdf, else { URDF2SDF u2g; - TiXmlDocument doc = u2g.InitModelString(_xmlString); + tinyxml2::XMLDocument doc; + u2g.InitModelString(_xmlString, &doc); + if (sdf::readDoc(&doc, _sdf, "urdf string", _convert, _errors)) { sdfdbg << "Parsing from urdf.\n"; @@ -520,11 +521,11 @@ bool readString(const std::string &_xmlString, ElementPtr _sdf) ////////////////////////////////////////////////// bool readString(const std::string &_xmlString, ElementPtr _sdf, Errors &_errors) { - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(_xmlString.c_str()); if (xmlDoc.Error()) { - sdferr << "Error parsing XML from string: " << xmlDoc.ErrorDesc() << '\n'; + sdferr << "Error parsing XML from string: " << xmlDoc.ErrorStr() << '\n'; return false; } if (readDoc(&xmlDoc, _sdf, "data-string", true, _errors)) @@ -540,7 +541,7 @@ bool readString(const std::string &_xmlString, ElementPtr _sdf, Errors &_errors) } ////////////////////////////////////////////////// -bool readDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf, +bool readDoc(tinyxml2::XMLDocument *_xmlDoc, SDFPtr _sdf, const std::string &_source, bool _convert, Errors &_errors) { if (!_xmlDoc) @@ -550,7 +551,7 @@ bool readDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf, } // check sdf version - TiXmlElement *sdfNode = _xmlDoc->FirstChildElement("sdf"); + tinyxml2::XMLElement *sdfNode = _xmlDoc->FirstChildElement("sdf"); if (!sdfNode) { return false; @@ -587,7 +588,7 @@ bool readDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf, } // parse new sdf xml - TiXmlElement *elemXml = _xmlDoc->FirstChildElement(_sdf->Root()->GetName()); + auto *elemXml = _xmlDoc->FirstChildElement(_sdf->Root()->GetName().c_str()); if (!readXml(elemXml, _sdf->Root(), _errors)) { _errors.push_back({ErrorCode::ELEMENT_INVALID, @@ -613,7 +614,7 @@ bool readDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf, } ////////////////////////////////////////////////// -bool readDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf, +bool readDoc(tinyxml2::XMLDocument *_xmlDoc, ElementPtr _sdf, const std::string &_source, bool _convert, Errors &_errors) { if (!_xmlDoc) @@ -623,7 +624,7 @@ bool readDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf, } // check sdf version - TiXmlElement *sdfNode = _xmlDoc->FirstChildElement("sdf"); + tinyxml2::XMLElement *sdfNode = _xmlDoc->FirstChildElement("sdf"); if (!sdfNode) { return false; @@ -648,11 +649,11 @@ bool readDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf, Converter::Convert(_xmlDoc, SDF::Version()); } - TiXmlElement *elemXml = sdfNode; + tinyxml2::XMLElement *elemXml = sdfNode; if (sdfNode->Value() != _sdf->GetName() && - sdfNode->FirstChildElement(_sdf->GetName())) + sdfNode->FirstChildElement(_sdf->GetName().c_str())) { - elemXml = sdfNode->FirstChildElement(_sdf->GetName()); + elemXml = sdfNode->FirstChildElement(_sdf->GetName().c_str()); } // parse new sdf xml @@ -680,18 +681,18 @@ bool readDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf, } ////////////////////////////////////////////////// -std::string getBestSupportedModelVersion(TiXmlElement *_modelXML, +std::string getBestSupportedModelVersion(tinyxml2::XMLElement *_modelXML, std::string &_modelFileName) { - TiXmlElement *sdfXML = _modelXML->FirstChildElement("sdf"); - TiXmlElement *nameSearch = _modelXML->FirstChildElement("name"); + tinyxml2::XMLElement *sdfXML = _modelXML->FirstChildElement("sdf"); + tinyxml2::XMLElement *nameSearch = _modelXML->FirstChildElement("name"); // If a match is not found, use the latest version of the element // that is not older than the SDF parser. ignition::math::SemanticVersion sdfParserVersion(SDF_VERSION); std::string bestVersionStr = "0.0"; - TiXmlElement *sdfSearch = sdfXML; + tinyxml2::XMLElement *sdfSearch = sdfXML; while (sdfSearch) { if (sdfSearch->Attribute("version")) @@ -769,16 +770,16 @@ std::string getModelFilePath(const std::string &_modelDirPath) } } - TiXmlDocument configFileDoc; - if (!configFileDoc.LoadFile(configFilePath)) + tinyxml2::XMLDocument configFileDoc; + if (tinyxml2::XML_SUCCESS != configFileDoc.LoadFile(configFilePath.c_str())) { sdferr << "Error parsing XML in file [" << configFilePath << "]: " - << configFileDoc.ErrorDesc() << '\n'; + << configFileDoc.ErrorStr() << '\n'; return std::string(); } - TiXmlElement *modelXML = configFileDoc.FirstChildElement("model"); + tinyxml2::XMLElement *modelXML = configFileDoc.FirstChildElement("model"); if (!modelXML) { @@ -796,7 +797,7 @@ std::string getModelFilePath(const std::string &_modelDirPath) } ////////////////////////////////////////////////// -bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors) +bool readXml(tinyxml2::XMLElement *_xml, ElementPtr _sdf, Errors &_errors) { // Check if the element pointer is deprecated. if (_sdf->GetRequired() == "-1") @@ -838,7 +839,7 @@ bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors) _sdf->Copy(refSDF); } - TiXmlAttribute *attribute = _xml->FirstAttribute(); + const tinyxml2::XMLAttribute *attribute = _xml->FirstAttribute(); unsigned int i = 0; @@ -851,7 +852,7 @@ bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors) { _sdf->AddAttribute(attribute->Name(), "string", "", 1, ""); _sdf->GetAttribute(attribute->Name())->SetFromString( - attribute->ValueStr()); + attribute->Value()); attribute = attribute->Next(); continue; } @@ -862,7 +863,7 @@ bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors) if (p->GetKey() == attribute->Name()) { // Set the value of the SDF attribute - if (!p->SetFromString(attribute->ValueStr())) + if (!p->SetFromString(attribute->Value())) { _errors.push_back({ErrorCode::ATTRIBUTE_INVALID, "Unable to read attribute[" + p->GetKey() + "]"}); @@ -904,7 +905,7 @@ bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors) std::string filename; // Iterate over all the child elements - TiXmlElement *elemXml = nullptr; + tinyxml2::XMLElement *elemXml = nullptr; for (elemXml = _xml->FirstChildElement(); elemXml; elemXml = elemXml->NextSiblingElement()) { @@ -1003,7 +1004,7 @@ bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors) elemXml->FirstChildElement("name")->GetText()); } - TiXmlElement *poseElemXml = elemXml->FirstChildElement("pose"); + tinyxml2::XMLElement *poseElemXml = elemXml->FirstChildElement("pose"); if (poseElemXml) { sdf::ElementPtr poseElem = topLevelElem->GetElement("pose"); @@ -1036,7 +1037,7 @@ bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors) if (isModel || isActor) { - for (TiXmlElement *childElemXml = elemXml->FirstChildElement(); + for (auto *childElemXml = elemXml->FirstChildElement(); childElemXml; childElemXml = childElemXml->NextSiblingElement()) { if (std::string("plugin") == childElemXml->Value()) @@ -1163,14 +1164,16 @@ static void replace_all(std::string &_str, } ///////////////////////////////////////////////// -void copyChildren(ElementPtr _sdf, TiXmlElement *_xml, const bool _onlyUnknown) +void copyChildren(ElementPtr _sdf, + tinyxml2::XMLElement *_xml, + const bool _onlyUnknown) { // Iterate over all the child elements - TiXmlElement *elemXml = nullptr; + tinyxml2::XMLElement *elemXml = nullptr; for (elemXml = _xml->FirstChildElement(); elemXml; elemXml = elemXml->NextSiblingElement()) { - std::string elem_name = elemXml->ValueStr(); + std::string elem_name = elemXml->Name(); if (_sdf->HasElementDescription(elem_name)) { @@ -1179,11 +1182,11 @@ void copyChildren(ElementPtr _sdf, TiXmlElement *_xml, const bool _onlyUnknown) sdf::ElementPtr element = _sdf->AddElement(elem_name); // FIXME: copy attributes - for (TiXmlAttribute *attribute = elemXml->FirstAttribute(); + for (const auto *attribute = elemXml->FirstAttribute(); attribute; attribute = attribute->Next()) { element->GetAttribute(attribute->Name())->SetFromString( - attribute->ValueStr()); + attribute->Value()); } // copy value @@ -1205,12 +1208,12 @@ void copyChildren(ElementPtr _sdf, TiXmlElement *_xml, const bool _onlyUnknown) element->AddValue("string", elemXml->GetText(), "1"); } - for (TiXmlAttribute *attribute = elemXml->FirstAttribute(); + for (const tinyxml2::XMLAttribute *attribute = elemXml->FirstAttribute(); attribute; attribute = attribute->Next()) { element->AddAttribute(attribute->Name(), "string", "", 1, ""); element->GetAttribute(attribute->Name())->SetFromString( - attribute->ValueStr()); + attribute->Value()); } copyChildren(element, elemXml, _onlyUnknown); @@ -1372,13 +1375,13 @@ bool convertFile(const std::string &_filename, const std::string &_version, return false; } - TiXmlDocument xmlDoc; - if (xmlDoc.LoadFile(filename)) + tinyxml2::XMLDocument xmlDoc; + if (!xmlDoc.LoadFile(filename.c_str())) { // read initial sdf version std::string originalVersion; { - TiXmlElement *sdfNode = xmlDoc.FirstChildElement("sdf"); + tinyxml2::XMLElement *sdfNode = xmlDoc.FirstChildElement("sdf"); if (sdfNode && sdfNode->Attribute("version")) { originalVersion = sdfNode->Attribute("version"); @@ -1417,7 +1420,7 @@ bool convertString(const std::string &_sdfString, const std::string &_version, return false; } - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; xmlDoc.Parse(_sdfString.c_str()); if (!xmlDoc.Error()) @@ -1425,7 +1428,7 @@ bool convertString(const std::string &_sdfString, const std::string &_version, // read initial sdf version std::string originalVersion; { - TiXmlElement *sdfNode = xmlDoc.FirstChildElement("sdf"); + tinyxml2::XMLElement *sdfNode = xmlDoc.FirstChildElement("sdf"); if (sdfNode && sdfNode->Attribute("version")) { originalVersion = sdfNode->Attribute("version"); diff --git a/src/parser_private.hh b/src/parser_private.hh index 40dfd7393..70160004f 100644 --- a/src/parser_private.hh +++ b/src/parser_private.hh @@ -17,7 +17,7 @@ #ifndef SDF_PARSER_PRIVATE_HH_ #define SDF_PARSER_PRIVATE_HH_ -#include +#include #include @@ -38,41 +38,41 @@ namespace sdf /// model XML tag /// \param[out] _modelFileName file name of the best model file /// \return string with the best SDF version supported - static std::string getBestSupportedModelVersion(TiXmlElement *_modelXML, - std::string &_modelFileName); + static std::string getBestSupportedModelVersion( + tinyxml2::XMLElement *_modelXML, std::string &_modelFileName); - /// \brief Initialize the SDF interface using a TinyXML document. + /// \brief Initialize the SDF interface using a TinyXML2 document. /// /// This actually forwards to initXml after converting the inputs - /// \param[in] _xmlDoc TinyXML document containing the SDFormat description + /// \param[in] _xmlDoc TinyXML2 document containing the SDFormat description /// file that corresponds with the input SDFPtr /// \param[in] _sdf SDF interface to be initialized - static bool initDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf); + static bool initDoc(tinyxml2::XMLDocument *_xmlDoc, SDFPtr _sdf); - /// \brief Initialize the SDF Element using a TinyXML document + /// \brief Initialize the SDF Element using a TinyXML2 document /// /// This actually forwards to initXml after converting the inputs - /// \param[in] _xmlDoc TinyXML document containing the SDFormat description + /// \param[in] _xmlDoc TinyXML2 document containing the SDFormat description /// file that corresponds with the input ElementPtr /// \param[in] _sdf SDF Element to be initialized - static bool initDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf); + static bool initDoc(tinyxml2::XMLDocument *_xmlDoc, ElementPtr _sdf); /// \brief Initialize the SDF Element by parsing the SDFormat description in - /// the input TinyXML element. This is where SDFormat spec/description files + /// the input TinyXML2 element. This is where SDFormat spec/description files /// are parsed /// \remark For internal use only. Do not use this function. - /// \param[in] _xml TinyXML element containing the SDFormat description + /// \param[in] _xml TinyXML2 element containing the SDFormat description /// file that corresponds with the input ElementPtr /// \param[in] _sdf SDF ElementPtr to be initialized - static bool initXml(TiXmlElement *_xml, ElementPtr _sdf); + static bool initXml(tinyxml2::XMLElement *_xml, ElementPtr _sdf); /// \brief Populate the SDF values from a TinyXML document - static bool readDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf, + static bool readDoc(tinyxml2::XMLDocument *_xmlDoc, SDFPtr _sdf, const std::string &_source, bool _convert, Errors &_errors); /// \brief Populate the SDF values from a TinyXML document - static bool readDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf, + static bool readDoc(tinyxml2::XMLDocument *_xmlDoc, ElementPtr _sdf, const std::string &_source, bool _convert, Errors &_errors); /// \brief Populate an SDF Element from the XML input. The XML input here is @@ -83,7 +83,9 @@ namespace sdf /// \param[in,out] _sdf SDF pointer to parse data into. /// \param[out] _errors Captures errors found during parsing. /// \return True on success, false on error. - static bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors); + static bool readXml(tinyxml2::XMLElement *_xml, + ElementPtr _sdf, + Errors &_errors); /// \brief Copy child XML elements into the _sdf element. /// \param[in] _sdf Parent Element. @@ -91,7 +93,7 @@ namespace sdf /// copied. /// \param[in] _onlyUnknown True to copy only elements that are NOT part of /// the SDF spec. Set this to false to copy everything. - static void copyChildren(ElementPtr _sdf, TiXmlElement *_xml, + static void copyChildren(ElementPtr _sdf, tinyxml2::XMLElement *_xml, const bool _onlyUnknown); } } diff --git a/src/parser_urdf.cc b/src/parser_urdf.cc index 27d786125..85eebbaa9 100644 --- a/src/parser_urdf.cc +++ b/src/parser_urdf.cc @@ -33,6 +33,7 @@ #include "sdf/sdf.hh" +#include "XmlUtils.hh" #include "SDFExtension.hh" #include "parser_urdf.hh" @@ -40,7 +41,10 @@ using namespace sdf; namespace sdf { inline namespace SDF_VERSION_NAMESPACE { -typedef std::shared_ptr TiXmlElementPtr; + +using XMLDocumentPtr = std::shared_ptr; +using XMLElementPtr = std::shared_ptr; + typedef std::shared_ptr SDFExtensionPtr; typedef std::map > StringSDFExtensionPtrMap; @@ -63,23 +67,23 @@ const int g_outputDecimalPrecision = 16; /// \param[in] _key XML key where vector3 value might be /// \param[in] _scale scalar scale for the vector3 /// \return a urdf::Vector3 -urdf::Vector3 ParseVector3(TiXmlNode* _key, double _scale = 1.0); +urdf::Vector3 ParseVector3(tinyxml2::XMLNode *_key, double _scale = 1.0); urdf::Vector3 ParseVector3(const std::string &_str, double _scale = 1.0); /// insert extensions into collision geoms -void InsertSDFExtensionCollision(TiXmlElement *_elem, +void InsertSDFExtensionCollision(tinyxml2::XMLElement *_elem, const std::string &_linkName); /// insert extensions into model -void InsertSDFExtensionRobot(TiXmlElement *_elem); +void InsertSDFExtensionRobot(tinyxml2::XMLElement *_elem); /// insert extensions into visuals -void InsertSDFExtensionVisual(TiXmlElement *_elem, +void InsertSDFExtensionVisual(tinyxml2::XMLElement *_elem, const std::string &_linkName); /// insert extensions into joints -void InsertSDFExtensionJoint(TiXmlElement *_elem, +void InsertSDFExtensionJoint(tinyxml2::XMLElement *_elem, const std::string &_jointName); /// reduced fixed joints: check if a fixed joint should be lumped @@ -90,13 +94,13 @@ bool FixedJointShouldBeReduced(urdf::JointSharedPtr _jnt); /// reduced fixed joints: apply transform reduction for ray sensors /// in extensions when doing fixed joint reduction void ReduceSDFExtensionSensorTransformReduction( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, ignition::math::Pose3d _reductionTransform); /// reduced fixed joints: apply transform reduction for projectors in /// extensions when doing fixed joint reduction void ReduceSDFExtensionProjectorTransformReduction( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, ignition::math::Pose3d _reductionTransform); @@ -117,65 +121,69 @@ void ReduceVisualsToParent(urdf::LinkSharedPtr _link); void ReduceInertialToParent(urdf::LinkSharedPtr /*_link*/); /// create SDF Collision block based on URDF -void CreateCollision(TiXmlElement* _elem, urdf::LinkConstSharedPtr _link, +void CreateCollision(tinyxml2::XMLElement* _elem, + urdf::LinkConstSharedPtr _link, urdf::CollisionSharedPtr _collision, const std::string &_oldLinkName = std::string("")); /// create SDF Visual block based on URDF -void CreateVisual(TiXmlElement *_elem, urdf::LinkConstSharedPtr _link, +void CreateVisual(tinyxml2::XMLElement *_elem, urdf::LinkConstSharedPtr _link, urdf::VisualSharedPtr _visual, const std::string &_oldLinkName = std::string("")); /// create SDF Joint block based on URDF -void CreateJoint(TiXmlElement *_root, urdf::LinkConstSharedPtr _link, +void CreateJoint(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link, ignition::math::Pose3d &_currentTransform); /// insert extensions into links -void InsertSDFExtensionLink(TiXmlElement *_elem, const std::string &_linkName); +void InsertSDFExtensionLink(tinyxml2::XMLElement *_elem, + const std::string &_linkName); /// create visual blocks from urdf visuals -void CreateVisuals(TiXmlElement* _elem, urdf::LinkConstSharedPtr _link); +void CreateVisuals(tinyxml2::XMLElement* _elem, urdf::LinkConstSharedPtr _link); /// create collision blocks from urdf collisions -void CreateCollisions(TiXmlElement* _elem, urdf::LinkConstSharedPtr _link); +void CreateCollisions(tinyxml2::XMLElement* _elem, + urdf::LinkConstSharedPtr _link); /// create SDF Inertial block based on URDF -void CreateInertial(TiXmlElement *_elem, urdf::LinkConstSharedPtr _link); +void CreateInertial(tinyxml2::XMLElement *_elem, + urdf::LinkConstSharedPtr _link); /// append transform (pose) to the end of the xml element -void AddTransform(TiXmlElement *_elem, +void AddTransform(tinyxml2::XMLElement *_elem, const ignition::math::Pose3d &_transform); /// create SDF from URDF link -void CreateSDF(TiXmlElement *_root, urdf::LinkConstSharedPtr _link, +void CreateSDF(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link, const ignition::math::Pose3d &_transform); /// create SDF Link block based on URDF -void CreateLink(TiXmlElement *_root, urdf::LinkConstSharedPtr _link, +void CreateLink(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link, ignition::math::Pose3d &_currentTransform); /// reduced fixed joints: apply appropriate frame updates in joint /// inside urdf extensions when doing fixed joint reduction void ReduceSDFExtensionJointFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link); /// reduced fixed joints: apply appropriate frame updates in gripper /// inside urdf extensions when doing fixed joint reduction void ReduceSDFExtensionGripperFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link); /// reduced fixed joints: apply appropriate frame updates in projector /// inside urdf extensions when doing fixed joint reduction void ReduceSDFExtensionProjectorFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link); /// reduced fixed joints: apply appropriate frame updates in plugins /// inside urdf extensions when doing fixed joint reduction void ReduceSDFExtensionPluginFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link, const std::string &_pluginName, const std::string &_elementName, ignition::math::Pose3d _reductionTransform); @@ -183,7 +191,7 @@ void ReduceSDFExtensionPluginFrameReplace( /// reduced fixed joints: apply appropriate frame updates in urdf /// extensions when doing fixed joint reduction void ReduceSDFExtensionContactSensorFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link); /// \brief reduced fixed joints: apply appropriate updates to urdf @@ -204,13 +212,13 @@ void ReduceSDFExtensionFrameReplace(SDFExtensionPtr _ge, urdf::LinkSharedPtr _link); /// get value from pair and return it as string -std::string GetKeyValueAsString(TiXmlElement* _elem); +std::string GetKeyValueAsString(tinyxml2::XMLElement* _elem); /// \brief append key value pair to the end of the xml element /// \param[in] _elem pointer to xml element /// \param[in] _key string containing key to add to xml element /// \param[in] _value string containing value for the key added -void AddKeyValue(TiXmlElement *_elem, const std::string &_key, +void AddKeyValue(tinyxml2::XMLElement *_elem, const std::string &_key, const std::string &_value); /// \brief convert values to string @@ -219,7 +227,8 @@ void AddKeyValue(TiXmlElement *_elem, const std::string &_key, /// \return a string std::string Values2str(unsigned int _count, const double *_values); -void CreateGeometry(TiXmlElement *_elem, urdf::GeometrySharedPtr _geometry); +void CreateGeometry(tinyxml2::XMLElement *_elem, + urdf::GeometrySharedPtr _geometry); ignition::math::Pose3d inverseTransformToParentFrame( ignition::math::Pose3d _transformInLinkFrame, @@ -250,13 +259,13 @@ urdf::Pose CopyPose(ignition::math::Pose3d _pose); //////////////////////////////////////////////////////////////////////////////// bool URDF2SDF::IsURDF(const std::string &_filename) { - TiXmlDocument xmlDoc; + tinyxml2::XMLDocument xmlDoc; - if (xmlDoc.LoadFile(_filename)) + if (tinyxml2::XML_SUCCESS == xmlDoc.LoadFile(_filename.c_str())) { - std::ostringstream stream; - stream << xmlDoc; - std::string urdfStr = stream.str(); + tinyxml2::XMLPrinter printer; + xmlDoc.Print(&printer); + std::string urdfStr = printer.CStr(); urdf::ModelInterfaceSharedPtr robotModel = urdf::parseURDF(urdfStr); return robotModel != nullptr; } @@ -299,11 +308,11 @@ urdf::Vector3 ParseVector3(const std::string &_str, double _scale) } ///////////////////////////////////////////////// -urdf::Vector3 ParseVector3(TiXmlNode *_key, double _scale) +urdf::Vector3 ParseVector3(tinyxml2::XMLNode *_key, double _scale) { if (_key != nullptr) { - TiXmlElement *key = _key->ToElement(); + tinyxml2::XMLElement *key = _key->ToElement(); if (key != nullptr) { return ParseVector3(GetKeyValueAsString(key), _scale); @@ -402,7 +411,7 @@ void ReduceVisualToParent(urdf::LinkSharedPtr _parentLink, //////////////////////////////////////////////////////////////////////////////// /// reduce fixed joints by lumping inertial, visual and // collision elements of the child link into the parent link -void ReduceFixedJoints(TiXmlElement *_root, urdf::LinkSharedPtr _link) +void ReduceFixedJoints(tinyxml2::XMLElement *_root, urdf::LinkSharedPtr _link) { // if child is attached to self by fixed _link first go up the tree, // check it's children recursively @@ -1125,10 +1134,10 @@ std::string Values2str(unsigned int _count, const int *_values) } //////////////////////////////////////////////////////////////////////////////// -void AddKeyValue(TiXmlElement *_elem, const std::string &_key, +void AddKeyValue(tinyxml2::XMLElement *_elem, const std::string &_key, const std::string &_value) { - TiXmlElement* childElem = _elem->FirstChildElement(_key); + tinyxml2::XMLElement *childElem = _elem->FirstChildElement(_key.c_str()); if (childElem) { std::string oldValue = GetKeyValueAsString(childElem); @@ -1145,17 +1154,19 @@ void AddKeyValue(TiXmlElement *_elem, const std::string &_key, << "> exists with [" << _value << "] due to fixed joint reduction.\n"; } - _elem->RemoveChild(childElem); // remove old _elem + _elem->DeleteChild(childElem); // remove old _elem } - TiXmlElement *ekey = new TiXmlElement(_key); - TiXmlText *textEkey = new TiXmlText(_value); + auto *doc = _elem->GetDocument(); + tinyxml2::XMLElement *ekey = doc->NewElement(_key.c_str()); + tinyxml2::XMLText *textEkey = doc->NewText(_value.c_str()); ekey->LinkEndChild(textEkey); _elem->LinkEndChild(ekey); } //////////////////////////////////////////////////////////////////////////////// -void AddTransform(TiXmlElement *_elem, const ignition::math::Pose3d &_transform) +void AddTransform(tinyxml2::XMLElement *_elem, + const ignition::math::Pose3d &_transform) { ignition::math::Vector3d e = _transform.Rot().Euler(); double cpose[6] = { _transform.Pos().X(), _transform.Pos().Y(), @@ -1166,7 +1177,7 @@ void AddTransform(TiXmlElement *_elem, const ignition::math::Pose3d &_transform) } //////////////////////////////////////////////////////////////////////////////// -std::string GetKeyValueAsString(TiXmlElement* _elem) +std::string GetKeyValueAsString(tinyxml2::XMLElement* _elem) { std::string valueStr; if (_elem->Attribute("value")) @@ -1174,20 +1185,25 @@ std::string GetKeyValueAsString(TiXmlElement* _elem) valueStr = _elem->Attribute("value"); } else if (_elem->FirstChild()) - /// @todo: FIXME: comment out check for now, different tinyxml - /// versions fails to compile: - // && _elem->FirstChild()->Type() == TiXmlNode::TINYXML_TEXT) { - valueStr = _elem->FirstChild()->ValueStr(); + // Check that this node is a XMLText + if (_elem->FirstChild()->ToText()) + { + valueStr = _elem->FirstChild()->Value(); + } + else + { + sdfwarn << "Attribute value string not set\n"; + } } - return valueStr; + return trim(valueStr); } ///////////////////////////////////////////////// -void ParseRobotOrigin(TiXmlDocument &_urdfXml) +void ParseRobotOrigin(tinyxml2::XMLDocument &_urdfXml) { - TiXmlElement *robotXml = _urdfXml.FirstChildElement("robot"); - TiXmlElement *originXml = robotXml->FirstChildElement("origin"); + tinyxml2::XMLElement *robotXml = _urdfXml.FirstChildElement("robot"); + tinyxml2::XMLElement *originXml = robotXml->FirstChildElement("origin"); if (originXml) { const char *xyzstr = originXml->Attribute("xyz"); @@ -1215,7 +1231,7 @@ void ParseRobotOrigin(TiXmlDocument &_urdfXml) } ///////////////////////////////////////////////// -void InsertRobotOrigin(TiXmlElement *_elem) +void InsertRobotOrigin(tinyxml2::XMLElement *_elem) { if (g_initialRobotPoseValid) { @@ -1230,14 +1246,14 @@ void InsertRobotOrigin(TiXmlElement *_elem) } //////////////////////////////////////////////////////////////////////////////// -void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) +void URDF2SDF::ParseSDFExtension(tinyxml2::XMLDocument &_urdfXml) { - TiXmlElement* robotXml = _urdfXml.FirstChildElement("robot"); + tinyxml2::XMLElement* robotXml = _urdfXml.FirstChildElement("robot"); // Get all SDF extension elements, put everything in // g_extensions map, containing a key string // (link/joint name) and values - for (TiXmlElement* sdfXml = robotXml->FirstChildElement("gazebo"); + for (tinyxml2::XMLElement* sdfXml = robotXml->FirstChildElement("gazebo"); sdfXml; sdfXml = sdfXml->NextSiblingElement("gazebo")) { const char* ref = sdfXml->Attribute("reference"); @@ -1264,7 +1280,7 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) SDFExtensionPtr sdf(new SDFExtension()); // begin parsing xml node - for (TiXmlElement *childElem = sdfXml->FirstChildElement(); + for (tinyxml2::XMLElement *childElem = sdfXml->FirstChildElement(); childElem; childElem = childElem->NextSiblingElement()) { sdf->oldLinkName = refStr; @@ -1275,12 +1291,12 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) // objects // material - if (childElem->ValueStr() == "material") + if (strcmp(childElem->Name(), "material") == 0) { sdf->material = GetKeyValueAsString(childElem); } - else if (childElem->ValueStr() == "collision" - || childElem->ValueStr() == "visual") + else if (strcmp(childElem->Name(), "collision") == 0 + || strcmp(childElem->Name(), "visual") == 0) { // anything inside of collision or visual tags: // @@ -1303,29 +1319,27 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) // // a place to store converted doc - for (TiXmlElement* e = childElem->FirstChildElement(); e; + for (tinyxml2::XMLElement* e = childElem->FirstChildElement(); e; e = e->NextSiblingElement()) { - TiXmlDocument xmlNewDoc; + tinyxml2::XMLPrinter printer; + e->Accept(&printer); - std::ostringstream origStream; - origStream << *e; - xmlNewDoc.Parse(origStream.str().c_str()); + XMLDocumentPtr xmlDocBlob(new tinyxml2::XMLDocument); + xmlDocBlob->Parse(printer.CStr()); // save all unknown stuff in a vector of blobs - TiXmlElementPtr blob( - new TiXmlElement(*xmlNewDoc.FirstChildElement())); - if (childElem->ValueStr() == "collision") + if (strcmp(childElem->Name(), "collision") == 0) { - sdf->collision_blobs.push_back(blob); + sdf->collision_blobs.push_back(xmlDocBlob); } else { - sdf->visual_blobs.push_back(blob); + sdf->visual_blobs.push_back(xmlDocBlob); } } } - else if (childElem->ValueStr() == "static") + else if (strcmp(childElem->Name(), "static") == 0) { std::string valueStr = GetKeyValueAsString(childElem); @@ -1340,7 +1354,7 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) sdf->setStaticFlag = false; } } - else if (childElem->ValueStr() == "turnGravityOff") + else if (strcmp(childElem->Name(), "turnGravityOff") == 0) { std::string valueStr = GetKeyValueAsString(childElem); @@ -1355,46 +1369,46 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) sdf->gravity = false; } } - else if (childElem->ValueStr() == "dampingFactor") + else if (strcmp(childElem->Name(), "dampingFactor") == 0) { sdf->isDampingFactor = true; sdf->dampingFactor = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "maxVel") + else if (strcmp(childElem->Name(), "maxVel") == 0) { sdf->isMaxVel = true; sdf->maxVel = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "minDepth") + else if (strcmp(childElem->Name(), "minDepth") == 0) { sdf->isMinDepth = true; sdf->minDepth = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "mu1") + else if (strcmp(childElem->Name(), "mu1") == 0) { sdf->isMu1 = true; sdf->mu1 = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "mu2") + else if (strcmp(childElem->Name(), "mu2") == 0) { sdf->isMu2 = true; sdf->mu2 = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "fdir1") + else if (strcmp(childElem->Name(), "fdir1") == 0) { sdf->fdir1 = GetKeyValueAsString(childElem); } - else if (childElem->ValueStr() == "kp") + else if (strcmp(childElem->Name(), "kp") == 0) { sdf->isKp = true; sdf->kp = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "kd") + else if (strcmp(childElem->Name(), "kd") == 0) { sdf->isKd = true; sdf->kd = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "selfCollide") + else if (strcmp(childElem->Name(), "selfCollide") == 0) { sdf->isSelfCollide = true; std::string valueStr = GetKeyValueAsString(childElem); @@ -1410,42 +1424,42 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) sdf->selfCollide = false; } } - else if (childElem->ValueStr() == "maxContacts") + else if (strcmp(childElem->Name(), "maxContacts") == 0) { sdf->isMaxContacts = true; sdf->maxContacts = std::stoi(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "laserRetro") + else if (strcmp(childElem->Name(), "laserRetro") == 0) { sdf->isLaserRetro = true; sdf->laserRetro = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "springReference") + else if (strcmp(childElem->Name(), "springReference") == 0) { sdf->isSpringReference = true; sdf->springReference = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "springStiffness") + else if (strcmp(childElem->Name(), "springStiffness") == 0) { sdf->isSpringStiffness = true; sdf->springStiffness = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "stopCfm") + else if (strcmp(childElem->Name(), "stopCfm") == 0) { sdf->isStopCfm = true; sdf->stopCfm = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "stopErp") + else if (strcmp(childElem->Name(), "stopErp") == 0) { sdf->isStopErp = true; sdf->stopErp = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "fudgeFactor") + else if (strcmp(childElem->Name(), "fudgeFactor") == 0) { sdf->isFudgeFactor = true; sdf->fudgeFactor = std::stod(GetKeyValueAsString(childElem)); } - else if (childElem->ValueStr() == "provideFeedback") + else if (strcmp(childElem->Name(), "provideFeedback") == 0) { sdf->isProvideFeedback = true; std::string valueStr = GetKeyValueAsString(childElem); @@ -1460,14 +1474,14 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) sdf->provideFeedback = false; } } - else if (childElem->ValueStr() == "canonicalBody") + else if (strcmp(childElem->Name(), "canonicalBody") == 0) { sdfdbg << "do nothing with canonicalBody\n"; } - else if (childElem->ValueStr() == "cfmDamping" || - childElem->ValueStr() == "implicitSpringDamper") + else if (strcmp(childElem->Name(), "cfmDamping") == 0 || + strcmp(childElem->Name(), "implicitSpringDamper") == 0) { - if (childElem->ValueStr() == "cfmDamping") + if (strcmp(childElem->Name(), "cfmDamping") == 0) { sdfwarn << "Note that cfmDamping is being deprecated by " << "implicitSpringDamper, please replace instances " @@ -1487,7 +1501,7 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) sdf->implicitSpringDamper = false; } } - else if (childElem->ValueStr() == "disableFixedJointLumping") + else if (strcmp(childElem->Name(), "disableFixedJointLumping") == 0) { std::string valueStr = GetKeyValueAsString(childElem); @@ -1497,7 +1511,7 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) g_fixedJointsTransformedInRevoluteJoints.insert(refStr); } } - else if (childElem->ValueStr() == "preserveFixedJoint") + else if (strcmp(childElem->Name(), "preserveFixedJoint") == 0) { std::string valueStr = GetKeyValueAsString(childElem); @@ -1510,17 +1524,16 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) else { // a place to store converted doc - TiXmlDocument xmlNewDoc; + XMLDocumentPtr xmlNewDoc(new tinyxml2::XMLDocument); + tinyxml2::XMLPrinter printer; + childElem->Accept(&printer); + xmlNewDoc->Parse(printer.CStr()); - std::ostringstream stream; - stream << *childElem; - sdfdbg << "extension [" << stream.str() << + sdfdbg << "extension [" << printer.CStr() << "] not converted from URDF, probably already in SDF format.\n"; - xmlNewDoc.Parse(stream.str().c_str()); // save all unknown stuff in a vector of blobs - TiXmlElementPtr blob(new TiXmlElement(*xmlNewDoc.FirstChildElement())); - sdf->blobs.push_back(blob); + sdf->blobs.push_back(xmlNewDoc); } } @@ -1542,8 +1555,27 @@ void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) } } +void CopyBlob(tinyxml2::XMLElement *_src, tinyxml2::XMLElement *_blob_parent) +{ + if (_blob_parent == nullptr) + { + sdferr << "blob parent is null\n"; + return; + } + + tinyxml2::XMLNode *clone = DeepClone(_blob_parent->GetDocument(), _src); + if (clone == nullptr) + { + sdferr << "Unable to deep copy blob\n"; + } + else + { + _blob_parent->LinkEndChild(clone); + } +} + //////////////////////////////////////////////////////////////////////////////// -void InsertSDFExtensionCollision(TiXmlElement *_elem, +void InsertSDFExtensionCollision(tinyxml2::XMLElement *_elem, const std::string &_linkName) { // loop through extensions for the whole model @@ -1561,11 +1593,11 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, // std::cerr << "working on g_extensions for link [" // << sdfIt->first << "]\n"; // if _elem already has a surface element, use it - TiXmlNode *surface = _elem->FirstChild("surface"); - TiXmlNode *friction = nullptr; - TiXmlNode *frictionOde = nullptr; - TiXmlNode *contact = nullptr; - TiXmlNode *contactOde = nullptr; + tinyxml2::XMLNode *surface = _elem->FirstChildElement("surface"); + tinyxml2::XMLNode *friction = nullptr; + tinyxml2::XMLNode *frictionOde = nullptr; + tinyxml2::XMLNode *contact = nullptr; + tinyxml2::XMLNode *contactOde = nullptr; // loop through all the gazebo extensions stored in sdfIt->second for (std::vector::iterator ge = sdfIt->second.begin(); @@ -1622,9 +1654,8 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, // explicitly specified fields (above). if (!(*ge)->collision_blobs.empty()) { - std::vector::iterator blob; - for (blob = (*ge)->collision_blobs.begin(); - blob != (*ge)->collision_blobs.end(); ++blob) + for (auto blob = (*ge)->collision_blobs.begin(); + blob != (*ge)->collision_blobs.end(); ++blob) { // find elements and assign pointers if they exist // for mu1, mu2, minDepth, maxVel, fdir1, kp, kd @@ -1632,14 +1663,7 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, // std::cerr << ">>>>> working on extension blob: [" // << (*blob)->Value() << "]\n"; - // print for debug - std::ostringstream origStream; - std::unique_ptr blobClone((*blob)->Clone()); - origStream << *blobClone; - // std::cerr << "collision extension [" - // << origStream.str() << "]\n"; - - if (strcmp((*blob)->Value(), "surface") == 0) + if (strcmp((*blob)->FirstChildElement()->Name(), "surface") == 0) { // blob is a , tread carefully otherwise // we end up with multiple copies of . @@ -1650,8 +1674,8 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, // do not exist, it simple, // just add it to the current collision // and it's done. - _elem->LinkEndChild((*blob)->Clone()); - surface = _elem->LastChild("surface"); + CopyBlob((*blob)->FirstChildElement(), _elem); + surface = _elem->LastChildElement("surface"); // std::cerr << " --- surface created " // << (void*)surface << "\n"; } @@ -1659,9 +1683,9 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, { // exist already, remove it and // overwrite with the blob. - _elem->RemoveChild(surface); - _elem->LinkEndChild((*blob)->Clone()); - surface = _elem->FirstChild("surface"); + _elem->DeleteChild(surface); + CopyBlob((*blob)->FirstChildElement(), _elem); + surface = _elem->FirstChildElement("surface"); // std::cerr << " --- surface exists, replace with blob.\n"; } @@ -1679,15 +1703,15 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, // "max_contacts" // Get contact[Ode] and friction[Ode] node pointers // if they exist. - contact = surface->FirstChild("contact"); + contact = surface->FirstChildElement("contact"); if (contact != nullptr) { - contactOde = contact->FirstChild("ode"); + contactOde = contact->FirstChildElement("ode"); } - friction = surface->FirstChild("friction"); + friction = surface->FirstChildElement("friction"); if (friction != nullptr) { - frictionOde = friction->FirstChild("ode"); + frictionOde = friction->FirstChildElement("ode"); } } else @@ -1695,7 +1719,7 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, // If the blob is not a , we don't have // to worry about backwards compatibility. // Simply add to master element. - _elem->LinkEndChild((*blob)->Clone()); + CopyBlob((*blob)->FirstChildElement(), _elem); } } } @@ -1717,9 +1741,10 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, // So there's no need for custom code for each property. // construct new elements if not in blobs + auto* doc = _elem->GetDocument(); if (surface == nullptr) { - surface = new TiXmlElement("surface"); + surface = doc->NewElement("surface"); if (!surface) { // Memory allocation error @@ -1732,9 +1757,9 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, // construct new elements if not in blobs if (contact == nullptr) { - if (surface->FirstChild("contact") == nullptr) + if (surface->FirstChildElement("contact") == nullptr) { - contact = new TiXmlElement("contact"); + contact = doc->NewElement("contact"); if (!contact) { // Memory allocation error @@ -1745,15 +1770,15 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, } else { - contact = surface->FirstChild("contact"); + contact = surface->FirstChildElement("contact"); } } if (contactOde == nullptr) { - if (contact->FirstChild("ode") == nullptr) + if (contact->FirstChildElement("ode") == nullptr) { - contactOde = new TiXmlElement("ode"); + contactOde = doc->NewElement("ode"); if (!contactOde) { // Memory allocation error @@ -1764,15 +1789,15 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, } else { - contactOde = contact->FirstChild("ode"); + contactOde = contact->FirstChildElement("ode"); } } if (friction == nullptr) { - if (surface->FirstChild("friction") == nullptr) + if (surface->FirstChildElement("friction") == nullptr) { - friction = new TiXmlElement("friction"); + friction = doc->NewElement("friction"); if (!friction) { // Memory allocation error @@ -1783,15 +1808,15 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, } else { - friction = surface->FirstChild("friction"); + friction = surface->FirstChildElement("friction"); } } if (frictionOde == nullptr) { - if (friction->FirstChild("ode") == nullptr) + if (friction->FirstChildElement("ode") == nullptr) { - frictionOde = new TiXmlElement("ode"); + frictionOde = doc->NewElement("ode"); if (!frictionOde) { // Memory allocation error @@ -1802,7 +1827,7 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, } else { - frictionOde = friction->FirstChild("ode"); + frictionOde = friction->FirstChildElement("ode"); } } @@ -1860,7 +1885,7 @@ void InsertSDFExtensionCollision(TiXmlElement *_elem, } //////////////////////////////////////////////////////////////////////////////// -void InsertSDFExtensionVisual(TiXmlElement *_elem, +void InsertSDFExtensionVisual(tinyxml2::XMLElement *_elem, const std::string &_linkName) { // loop through extensions for the whole model @@ -1878,8 +1903,8 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, // std::cerr << "working on g_extensions for link [" // << sdfIt->first << "]\n"; // if _elem already has a material element, use it - TiXmlNode *material = _elem->FirstChild("material"); - TiXmlElement *script = nullptr; + tinyxml2::XMLElement *material = _elem->FirstChildElement("material"); + tinyxml2::XMLElement *script = nullptr; // loop through all the gazebo extensions stored in sdfIt->second for (std::vector::iterator ge = sdfIt->second.begin(); @@ -1936,8 +1961,7 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, // explicitly specified fields (above). if (!(*ge)->visual_blobs.empty()) { - std::vector::iterator blob; - for (blob = (*ge)->visual_blobs.begin(); + for (auto blob = (*ge)->visual_blobs.begin(); blob != (*ge)->visual_blobs.end(); ++blob) { // find elements and assign pointers if they exist @@ -1952,7 +1976,7 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, // std::cerr << "visual extension [" // << origStream.str() << "]\n"; - if (strcmp((*blob)->Value(), "material") == 0) + if (strcmp((*blob)->FirstChildElement()->Name(), "material") == 0) { // blob is a , tread carefully otherwise // we end up with multiple copies of . @@ -1963,8 +1987,8 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, // do not exist, it simple, // just add it to the current visual // and it's done. - _elem->LinkEndChild((*blob)->Clone()); - material = _elem->LastChild("material"); + CopyBlob((*blob)->FirstChildElement(), _elem); + material = _elem->LastChildElement("material"); // std::cerr << " --- material created " // << (void*)material << "\n"; } @@ -1972,9 +1996,9 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, { // exist already, remove it and // overwrite with the blob. - _elem->RemoveChild(material); - _elem->LinkEndChild((*blob)->Clone()); - material = _elem->FirstChild("material"); + _elem->DeleteChild(material); + CopyBlob((*blob)->FirstChildElement(), _elem); + material = _elem->FirstChildElement("material"); // std::cerr << " --- material exists, replace with blob.\n"; } @@ -1993,7 +2017,7 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, // If the blob is not a , we don't have // to worry about backwards compatibility. // Simply add to master element. - _elem->LinkEndChild((*blob)->Clone()); + CopyBlob((*blob)->FirstChildElement(), _elem); } } } @@ -2014,7 +2038,7 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, // construct new elements if not in blobs if (material == nullptr) { - material = new TiXmlElement("material"); + material = _elem->GetDocument()->NewElement("material"); if (!material) { // Memory allocation error @@ -2028,7 +2052,7 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, { if (material->FirstChildElement("script") == nullptr) { - script = new TiXmlElement("script"); + script = _elem->GetDocument()->NewElement("script"); if (!script) { // Memory allocation error @@ -2039,7 +2063,7 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, } else { - script = material->FirstChildElement("script"); + script = material->FirstChildElement("script"); } } @@ -2055,7 +2079,8 @@ void InsertSDFExtensionVisual(TiXmlElement *_elem, } //////////////////////////////////////////////////////////////////////////////// -void InsertSDFExtensionLink(TiXmlElement *_elem, const std::string &_linkName) +void InsertSDFExtensionLink(tinyxml2::XMLElement *_elem, + const std::string &_linkName) { for (StringSDFExtensionPtrMap::iterator sdfIt = g_extensions.begin(); @@ -2079,7 +2104,9 @@ void InsertSDFExtensionLink(TiXmlElement *_elem, const std::string &_linkName) } // damping factor - TiXmlElement *velocityDecay = new TiXmlElement("velocity_decay"); + + tinyxml2::XMLElement *velocityDecay = + _elem->GetDocument()->NewElement("velocity_decay"); if ((*ge)->isDampingFactor) { /// @todo separate linear and angular velocity decay @@ -2095,11 +2122,10 @@ void InsertSDFExtensionLink(TiXmlElement *_elem, const std::string &_linkName) AddKeyValue(_elem, "self_collide", (*ge)->selfCollide ? "1" : "0"); } // insert blobs into body - for (std::vector::iterator - blobIt = (*ge)->blobs.begin(); + for (auto blobIt = (*ge)->blobs.begin(); blobIt != (*ge)->blobs.end(); ++blobIt) { - _elem->LinkEndChild((*blobIt)->Clone()); + CopyBlob((*blobIt)->FirstChildElement(), _elem); } } } @@ -2107,9 +2133,10 @@ void InsertSDFExtensionLink(TiXmlElement *_elem, const std::string &_linkName) } //////////////////////////////////////////////////////////////////////////////// -void InsertSDFExtensionJoint(TiXmlElement *_elem, +void InsertSDFExtensionJoint(tinyxml2::XMLElement *_elem, const std::string &_jointName) { + auto* doc = _elem->GetDocument(); for (StringSDFExtensionPtrMap::iterator sdfIt = g_extensions.begin(); sdfIt != g_extensions.end(); ++sdfIt) @@ -2120,43 +2147,43 @@ void InsertSDFExtensionJoint(TiXmlElement *_elem, ge = sdfIt->second.begin(); ge != sdfIt->second.end(); ++ge) { - TiXmlElement *physics = _elem->FirstChildElement("physics"); + tinyxml2::XMLElement *physics = _elem->FirstChildElement("physics"); bool newPhysics = false; if (physics == nullptr) { - physics = new TiXmlElement("physics"); + physics = doc->NewElement("physics"); newPhysics = true; } - TiXmlElement *physicsOde = physics->FirstChildElement("ode"); + tinyxml2::XMLElement *physicsOde = physics->FirstChildElement("ode"); bool newPhysicsOde = false; if (physicsOde == nullptr) { - physicsOde = new TiXmlElement("ode"); + physicsOde = doc->NewElement("ode"); newPhysicsOde = true; } - TiXmlElement *limit = physicsOde->FirstChildElement("limit"); + tinyxml2::XMLElement *limit = physicsOde->FirstChildElement("limit"); bool newLimit = false; if (limit == nullptr) { - limit = new TiXmlElement("limit"); + limit = doc->NewElement("limit"); newLimit = true; } - TiXmlElement *axis = _elem->FirstChildElement("axis"); + tinyxml2::XMLElement *axis = _elem->FirstChildElement("axis"); bool newAxis = false; if (axis == nullptr) { - axis = new TiXmlElement("axis"); + axis = doc->NewElement("axis"); newAxis = true; } - TiXmlElement *dynamics = axis->FirstChildElement("dynamics"); + tinyxml2::XMLElement *dynamics = axis->FirstChildElement("dynamics"); bool newDynamics = false; if (dynamics == nullptr) { - dynamics = new TiXmlElement("dynamics"); + dynamics = doc->NewElement("dynamics"); newDynamics = true; } @@ -2242,11 +2269,10 @@ void InsertSDFExtensionJoint(TiXmlElement *_elem, } // insert all additional blobs into joint - for (std::vector::iterator - blobIt = (*ge)->blobs.begin(); + for (auto blobIt = (*ge)->blobs.begin(); blobIt != (*ge)->blobs.end(); ++blobIt) { - _elem->LinkEndChild((*blobIt)->Clone()); + CopyBlob((*blobIt)->FirstChildElement(), _elem); } } } @@ -2254,7 +2280,7 @@ void InsertSDFExtensionJoint(TiXmlElement *_elem, } //////////////////////////////////////////////////////////////////////////////// -void InsertSDFExtensionRobot(TiXmlElement *_elem) +void InsertSDFExtensionRobot(tinyxml2::XMLElement *_elem) { for (StringSDFExtensionPtrMap::iterator sdfIt = g_extensions.begin(); @@ -2277,13 +2303,10 @@ void InsertSDFExtensionRobot(TiXmlElement *_elem) } // copy extension containing blobs and without reference - for (std::vector::iterator - blobIt = (*ge)->blobs.begin(); + for (auto blobIt = (*ge)->blobs.begin(); blobIt != (*ge)->blobs.end(); ++blobIt) { - std::ostringstream streamIn; - streamIn << *(*blobIt); - _elem->LinkEndChild((*blobIt)->Clone()); + CopyBlob((*blobIt)->FirstChildElement(), _elem); } } } @@ -2291,12 +2314,14 @@ void InsertSDFExtensionRobot(TiXmlElement *_elem) } //////////////////////////////////////////////////////////////////////////////// -void CreateGeometry(TiXmlElement* _elem, urdf::GeometrySharedPtr _geometry) +void CreateGeometry(tinyxml2::XMLElement* _elem, + urdf::GeometrySharedPtr _geometry) { - TiXmlElement *sdfGeometry = new TiXmlElement("geometry"); + auto* doc = _elem->GetDocument(); + tinyxml2::XMLElement *sdfGeometry = doc->NewElement("geometry"); std::string type; - TiXmlElement *geometryType = nullptr; + tinyxml2::XMLElement *geometryType = nullptr; switch (_geometry->type) { @@ -2310,7 +2335,7 @@ void CreateGeometry(TiXmlElement* _elem, urdf::GeometrySharedPtr _geometry) sizeVals[0] = box->dim.x; sizeVals[1] = box->dim.y; sizeVals[2] = box->dim.z; - geometryType = new TiXmlElement(type); + geometryType = doc->NewElement(type.c_str()); AddKeyValue(geometryType, "size", Values2str(sizeCount, sizeVals)); } break; @@ -2319,7 +2344,7 @@ void CreateGeometry(TiXmlElement* _elem, urdf::GeometrySharedPtr _geometry) { urdf::CylinderConstSharedPtr cylinder = urdf::dynamic_pointer_cast(_geometry); - geometryType = new TiXmlElement(type); + geometryType = doc->NewElement(type.c_str()); AddKeyValue(geometryType, "length", Values2str(1, &cylinder->length)); AddKeyValue(geometryType, "radius", Values2str(1, &cylinder->radius)); } @@ -2329,7 +2354,7 @@ void CreateGeometry(TiXmlElement* _elem, urdf::GeometrySharedPtr _geometry) { urdf::SphereConstSharedPtr sphere = urdf::dynamic_pointer_cast(_geometry); - geometryType = new TiXmlElement(type); + geometryType = doc->NewElement(type.c_str()); AddKeyValue(geometryType, "radius", Values2str(1, &sphere->radius)); } break; @@ -2338,7 +2363,7 @@ void CreateGeometry(TiXmlElement* _elem, urdf::GeometrySharedPtr _geometry) { urdf::MeshConstSharedPtr mesh = urdf::dynamic_pointer_cast(_geometry); - geometryType = new TiXmlElement(type); + geometryType = doc->NewElement(type.c_str()); AddKeyValue(geometryType, "scale", Vector32Str(mesh->scale)); // do something more to meshes { @@ -2497,7 +2522,8 @@ void ReduceSDFExtensionToParent(urdf::LinkSharedPtr _link) // find pointer to the existing extension with the new _link reference std::string parentLinkName = _link->getParent()->name; - auto parentExt = g_extensions.find(parentLinkName); + StringSDFExtensionPtrMap::iterator parentExt = + g_extensions.find(parentLinkName); // if none exist, create new extension with parentLinkName if (parentExt == g_extensions.end()) @@ -2547,16 +2573,15 @@ void ReduceSDFExtensionFrameReplace(SDFExtensionPtr _ge, // and it needs to be reparented to // base_footprint_collision sdfdbg << " STRING REPLACE: instances of _link name [" - << linkName << "] with [" << parentLinkName << "]\n"; - for (std::vector::iterator blobIt = _ge->blobs.begin(); - blobIt != _ge->blobs.end(); ++blobIt) + << linkName << "] with [" << parentLinkName << "]\n"; + for (auto blobIt = _ge->blobs.begin(); + blobIt != _ge->blobs.end(); ++blobIt) { - std::ostringstream debugStreamIn; - debugStreamIn << *(*blobIt); - std::string debugBlob = debugStreamIn.str(); + tinyxml2::XMLPrinter debugStreamIn; + (*blobIt)->Print(&debugStreamIn); sdfdbg << " INITIAL STRING link [" << linkName << "]-->[" << parentLinkName << "]: [" - << debugBlob << "]\n"; + << debugStreamIn.CStr() << "]\n"; ReduceSDFExtensionContactSensorFrameReplace(blobIt, _link); ReduceSDFExtensionPluginFrameReplace(blobIt, _link, @@ -2568,17 +2593,14 @@ void ReduceSDFExtensionFrameReplace(SDFExtensionPtr _ge, ReduceSDFExtensionProjectorFrameReplace(blobIt, _link); ReduceSDFExtensionGripperFrameReplace(blobIt, _link); ReduceSDFExtensionJointFrameReplace(blobIt, _link); - - std::ostringstream debugStreamOut; - debugStreamOut << *(*blobIt); } } //////////////////////////////////////////////////////////////////////////////// void ReduceSDFExtensionsTransform(SDFExtensionPtr _ge) { - for (std::vector::iterator blobIt = _ge->blobs.begin(); - blobIt != _ge->blobs.end(); ++blobIt) + for (auto blobIt = _ge->blobs.begin(); + blobIt != _ge->blobs.end(); ++blobIt) { /// @todo make sure we are not missing any additional transform reductions ReduceSDFExtensionSensorTransformReduction(blobIt, @@ -2604,13 +2626,12 @@ void URDF2SDF::ListSDFExtensions() sdfdbg << " PRINTING [" << static_cast((*ge)->blobs.size()) << "] BLOBS for extension [" << ++extCount << "] referencing [" << sdfIt->first << "]\n"; - for (std::vector::iterator - blobIt = (*ge)->blobs.begin(); + for (auto blobIt = (*ge)->blobs.begin(); blobIt != (*ge)->blobs.end(); ++blobIt) { - std::ostringstream streamIn; - streamIn << *(*blobIt); - sdfdbg << " BLOB: [" << streamIn.str() << "]\n"; + tinyxml2::XMLPrinter streamIn; + (*blobIt)->Print(&streamIn); + sdfdbg << " BLOB: [" << streamIn.CStr() << "]\n"; } } } @@ -2631,13 +2652,12 @@ void URDF2SDF::ListSDFExtensions(const std::string &_reference) for (std::vector::iterator ge = sdfIt->second.begin(); ge != sdfIt->second.end(); ++ge) { - for (std::vector::iterator - blobIt = (*ge)->blobs.begin(); + for (auto blobIt = (*ge)->blobs.begin(); blobIt != (*ge)->blobs.end(); ++blobIt) { - std::ostringstream streamIn; - streamIn << *(*blobIt); - sdfdbg << " BLOB: [" << streamIn.str() << "]\n"; + tinyxml2::XMLPrinter streamIn; + (*blobIt)->Print(&streamIn); + sdfdbg << " BLOB: [" << streamIn.CStr() << "]\n"; } } } @@ -2645,7 +2665,7 @@ void URDF2SDF::ListSDFExtensions(const std::string &_reference) } //////////////////////////////////////////////////////////////////////////////// -void CreateSDF(TiXmlElement *_root, +void CreateSDF(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link, const ignition::math::Pose3d &_transform) { @@ -2731,22 +2751,24 @@ urdf::Pose CopyPose(ignition::math::Pose3d _pose) } //////////////////////////////////////////////////////////////////////////////// -void CreateLink(TiXmlElement *_root, +void CreateLink(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link, ignition::math::Pose3d &_currentTransform) { // create new body - TiXmlElement *elem = new TiXmlElement("link"); + tinyxml2::XMLElement *elem = _root->GetDocument()->NewElement("link"); // set body name - elem->SetAttribute("name", _link->name); + elem->SetAttribute("name", _link->name.c_str()); + // compute global transform + ignition::math::Pose3d localTransform; // this is the transform from parent link to current _link // this transform does not exist for the root link if (_link->parent_joint) { - TiXmlElement *pose = new TiXmlElement("pose"); - pose->SetAttribute("relative_to", _link->parent_joint->name); + tinyxml2::XMLElement *pose = _root->GetDocument()->NewElement("pose"); + pose->SetAttribute("relative_to", _link->parent_joint->name.c_str()); elem->LinkEndChild(pose); } else @@ -2780,7 +2802,7 @@ void CreateLink(TiXmlElement *_root, } //////////////////////////////////////////////////////////////////////////////// -void CreateCollisions(TiXmlElement* _elem, +void CreateCollisions(tinyxml2::XMLElement* _elem, urdf::LinkConstSharedPtr _link) { // loop through all collisions in @@ -2825,7 +2847,7 @@ void CreateCollisions(TiXmlElement* _elem, } //////////////////////////////////////////////////////////////////////////////// -void CreateVisuals(TiXmlElement* _elem, +void CreateVisuals(tinyxml2::XMLElement* _elem, urdf::LinkConstSharedPtr _link) { // loop through all visuals in @@ -2870,10 +2892,11 @@ void CreateVisuals(TiXmlElement* _elem, } //////////////////////////////////////////////////////////////////////////////// -void CreateInertial(TiXmlElement *_elem, +void CreateInertial(tinyxml2::XMLElement *_elem, urdf::LinkConstSharedPtr _link) { - TiXmlElement *inertial = new TiXmlElement("inertial"); + auto* doc = _elem->GetDocument(); + tinyxml2::XMLElement *inertial = doc->NewElement("inertial"); // set mass properties // check and print a warning message @@ -2889,7 +2912,7 @@ void CreateInertial(TiXmlElement *_elem, Values2str(1, &_link->inertial->mass)); // add inertia (ixx, ixy, ixz, iyy, iyz, izz) - TiXmlElement *inertia = new TiXmlElement("inertia"); + tinyxml2::XMLElement *inertia = doc->NewElement("inertia"); AddKeyValue(inertia, "ixx", Values2str(1, &_link->inertial->ixx)); AddKeyValue(inertia, "ixy", @@ -2908,7 +2931,7 @@ void CreateInertial(TiXmlElement *_elem, } //////////////////////////////////////////////////////////////////////////////// -void CreateJoint(TiXmlElement *_root, +void CreateJoint(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link, ignition::math::Pose3d &/*_currentTransform*/) { @@ -2964,16 +2987,17 @@ void CreateJoint(TiXmlElement *_root, if (!jtype.empty()) { - TiXmlElement *joint = new TiXmlElement("joint"); + auto* doc = _root->GetDocument(); + tinyxml2::XMLElement *joint = doc->NewElement("joint"); if (jtype == "fixed" && fixedJointConvertedToRevoluteJoint) { joint->SetAttribute("type", "revolute"); } else { - joint->SetAttribute("type", jtype); + joint->SetAttribute("type", jtype.c_str()); } - joint->SetAttribute("name", _link->parent_joint->name); + joint->SetAttribute("name", _link->parent_joint->name.c_str()); // Add joint pose relative to parent link AddTransform( joint, CopyPose(_link->parent_joint->parent_to_joint_origin_transform)); @@ -2983,14 +3007,14 @@ void CreateJoint(TiXmlElement *_root, { relativeToAttr = "__model__"; } - pose->SetAttribute("relative_to", relativeToAttr); + pose->SetAttribute("relative_to", relativeToAttr.c_str()); AddKeyValue(joint, "parent", _link->getParent()->name); AddKeyValue(joint, "child", _link->name); - TiXmlElement *jointAxis = new TiXmlElement("axis"); - TiXmlElement *jointAxisLimit = new TiXmlElement("limit"); - TiXmlElement *jointAxisDynamics = new TiXmlElement("dynamics"); + tinyxml2::XMLElement *jointAxis = doc->NewElement("axis"); + tinyxml2::XMLElement *jointAxisLimit = doc->NewElement("limit"); + tinyxml2::XMLElement *jointAxisDynamics = doc->NewElement("dynamics"); if (jtype == "fixed" && fixedJointConvertedToRevoluteJoint) { AddKeyValue(jointAxisLimit, "lower", "0"); @@ -3057,11 +3081,11 @@ void CreateJoint(TiXmlElement *_root, if (jtype == "fixed" && !fixedJointConvertedToRevoluteJoint) { - delete jointAxisLimit; + doc->DeleteNode(jointAxisLimit); jointAxisLimit = 0; - delete jointAxisDynamics; + doc->DeleteNode(jointAxisDynamics); jointAxisDynamics = 0; - delete jointAxis; + doc->DeleteNode(jointAxis); jointAxis = 0; } else @@ -3080,12 +3104,14 @@ void CreateJoint(TiXmlElement *_root, } //////////////////////////////////////////////////////////////////////////////// -void CreateCollision(TiXmlElement* _elem, urdf::LinkConstSharedPtr _link, +void CreateCollision(tinyxml2::XMLElement* _elem, + urdf::LinkConstSharedPtr _link, urdf::CollisionSharedPtr _collision, const std::string &_oldLinkName) { + auto* doc = _elem->GetDocument(); // begin create geometry node, skip if no collision specified - TiXmlElement *sdfCollision = new TiXmlElement("collision"); + tinyxml2::XMLElement *sdfCollision = doc->NewElement("collision"); // std::cerr << "CreateCollision link [" << _link->name // << "] old [" << _oldLinkName @@ -3096,12 +3122,12 @@ void CreateCollision(TiXmlElement* _elem, urdf::LinkConstSharedPtr _link, if (_oldLinkName.compare(0, _link->name.size(), _link->name) == 0 || _oldLinkName.empty()) { - sdfCollision->SetAttribute("name", _oldLinkName); + sdfCollision->SetAttribute("name", _oldLinkName.c_str()); } else { - sdfCollision->SetAttribute("name", _link->name - + g_lumpPrefix + _oldLinkName); + sdfCollision->SetAttribute("name", (_link->name + + g_lumpPrefix + _oldLinkName).c_str()); } // std::cerr << "collision [" << sdfCollision->Attribute("name") << "]\n"; @@ -3133,21 +3159,23 @@ void CreateCollision(TiXmlElement* _elem, urdf::LinkConstSharedPtr _link, } //////////////////////////////////////////////////////////////////////////////// -void CreateVisual(TiXmlElement *_elem, urdf::LinkConstSharedPtr _link, +void CreateVisual(tinyxml2::XMLElement *_elem, urdf::LinkConstSharedPtr _link, urdf::VisualSharedPtr _visual, const std::string &_oldLinkName) { + auto* doc = _elem->GetDocument(); // begin create sdf visual node - TiXmlElement *sdfVisual = new TiXmlElement("visual"); + tinyxml2::XMLElement *sdfVisual = doc->NewElement("visual"); // set its name if (_oldLinkName.compare(0, _link->name.size(), _link->name) == 0 || _oldLinkName.empty()) { - sdfVisual->SetAttribute("name", _oldLinkName); + sdfVisual->SetAttribute("name", _oldLinkName.c_str()); } else { - sdfVisual->SetAttribute("name", _link->name + g_lumpPrefix + _oldLinkName); + sdfVisual->SetAttribute("name", + (_link->name + g_lumpPrefix + _oldLinkName).c_str()); } // add the visualisation transfrom @@ -3177,30 +3205,38 @@ void CreateVisual(TiXmlElement *_elem, urdf::LinkConstSharedPtr _link, } //////////////////////////////////////////////////////////////////////////////// -TiXmlDocument URDF2SDF::InitModelString(const std::string &_urdfStr, - bool _enforceLimits) +void URDF2SDF::InitModelString(const std::string &_urdfStr, + tinyxml2::XMLDocument* _sdfXmlOut, + bool _enforceLimits) { g_enforceLimits = _enforceLimits; // Create a RobotModel from string urdf::ModelInterfaceSharedPtr robotModel = urdf::parseURDF(_urdfStr); - // an xml object to hold the xml result - TiXmlDocument sdfXmlOut; - if (!robotModel) { sdferr << "Unable to call parseURDF on robot model\n"; - return sdfXmlOut; + return; } + // create root element and define needed namespaces + tinyxml2::XMLElement *robot = _sdfXmlOut->NewElement("model"); + + // set model name to urdf robot name if not specified + robot->SetAttribute("name", robotModel->getName().c_str()); + // initialize transform for the model, urdf is recursive, // while sdf defines all links relative to model frame ignition::math::Pose3d transform; // parse sdf extension - TiXmlDocument urdfXml; - urdfXml.Parse(_urdfStr.c_str()); + tinyxml2::XMLDocument urdfXml; + if (urdfXml.Parse(_urdfStr.c_str())) + { + sdferr << "Unable to parse URDF string: " << urdfXml.ErrorStr() << "\n"; + return; + } g_extensions.clear(); g_fixedJointsTransformedInFixedJoints.clear(); g_fixedJointsTransformedInRevoluteJoints.clear(); @@ -3210,16 +3246,12 @@ TiXmlDocument URDF2SDF::InitModelString(const std::string &_urdfStr, ParseRobotOrigin(urdfXml); urdf::LinkConstSharedPtr rootLink = robotModel->getRoot(); - - // create root element and define needed namespaces - TiXmlElement *robot = new TiXmlElement("model"); - - TiXmlElement *sdf; + tinyxml2::XMLElement *sdf; try { // set model name to urdf robot name if not specified - robot->SetAttribute("name", robotModel->getName()); + robot->SetAttribute("name", robotModel->getName().c_str()); // Fixed Joint Reduction // if link connects to parent via fixed joint, lump down and remove link @@ -3255,7 +3287,7 @@ TiXmlDocument URDF2SDF::InitModelString(const std::string &_urdfStr, InsertRobotOrigin(robot); // Create new sdf - sdf = new TiXmlElement("sdf"); + sdf = _sdfXmlOut->NewElement("sdf"); try { @@ -3267,44 +3299,41 @@ TiXmlDocument URDF2SDF::InitModelString(const std::string &_urdfStr, } catch(...) { - delete sdf; throw; } } catch(...) { - delete robot; throw; } - sdfXmlOut.LinkEndChild(sdf); - - return sdfXmlOut; + _sdfXmlOut->LinkEndChild(sdf); } //////////////////////////////////////////////////////////////////////////////// -TiXmlDocument URDF2SDF::InitModelDoc(TiXmlDocument* _xmlDoc) +void URDF2SDF::InitModelDoc(const tinyxml2::XMLDocument *_xmlDoc, + tinyxml2::XMLDocument *_sdfXmlDoc) { - std::ostringstream stream; - stream << *_xmlDoc; - std::string urdfStr = stream.str(); - return InitModelString(urdfStr); + tinyxml2::XMLPrinter printer; + _xmlDoc->Print(&printer); + std::string urdfStr = printer.CStr(); + InitModelString(urdfStr, _sdfXmlDoc); } //////////////////////////////////////////////////////////////////////////////// -TiXmlDocument URDF2SDF::InitModelFile(const std::string &_filename) +void URDF2SDF::InitModelFile(const std::string &_filename, + tinyxml2::XMLDocument *_sdfXmlDoc) { - TiXmlDocument xmlDoc; - if (xmlDoc.LoadFile(_filename)) + tinyxml2::XMLDocument xmlDoc; + if (!xmlDoc.LoadFile(_filename.c_str())) { - return this->InitModelDoc(&xmlDoc); + this->InitModelDoc(&xmlDoc, _sdfXmlDoc); } else { - sdferr << "Unable to load file[" << _filename << "].\n"; + sdferr << "Unable to load file[" + << _filename << "]:" << xmlDoc.ErrorStr() << "\n"; } - - return xmlDoc; } //////////////////////////////////////////////////////////////////////////////// @@ -3322,31 +3351,31 @@ bool FixedJointShouldBeReduced(urdf::JointSharedPtr _jnt) //////////////////////////////////////////////////////////////////////////////// void ReduceSDFExtensionSensorTransformReduction( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, ignition::math::Pose3d _reductionTransform) { // overwrite and if they exist - if ((*_blobIt)->ValueStr() == "sensor") + if ( strcmp((*_blobIt)->FirstChildElement()->Name(), "sensor") == 0) { // parse it and add/replace the reduction transform // find first instance of xyz and rpy, replace with reduction transform // debug print - // for (TiXmlNode* elIt = (*_blobIt)->FirstChild(); + // for (tinyxml2::XMLNode* elIt = (*_blobIt)->FirstChild(); // elIt; elIt = elIt->NextSibling()) // { - // std::ostringstream streamIn; - // streamIn << *elIt; - // sdfdbg << " " << streamIn << "\n"; + // tinyxml2::XMLPrinter streamIn; + // elIt->Accept(&streamIn); + // sdfdbg << " " << streamIn.CStr() << "\n"; // } { - TiXmlNode* oldPoseKey = (*_blobIt)->FirstChild("pose"); + tinyxml2::XMLNode *oldPoseKey = (*_blobIt)->FirstChildElement("pose"); /// @todo: FIXME: we should read xyz, rpy and aggregate it to /// reductionTransform instead of just throwing the info away. if (oldPoseKey) { - (*_blobIt)->RemoveChild(oldPoseKey); + (*_blobIt)->DeleteChild(oldPoseKey); } } @@ -3367,9 +3396,11 @@ void ReduceSDFExtensionSensorTransformReduction( poseStream << reductionXyz.x << " " << reductionXyz.y << " " << reductionXyz.z << " " << reductionRpy.x << " " << reductionRpy.y << " " << reductionRpy.z; - TiXmlText* poseTxt = new TiXmlText(poseStream.str()); - TiXmlElement* poseKey = new TiXmlElement("pose"); + auto* doc = (*_blobIt)->GetDocument(); + tinyxml2::XMLText *poseTxt = doc->NewText(poseStream.str().c_str()); + tinyxml2::XMLElement *poseKey = doc->NewElement("pose"); + poseKey->LinkEndChild(poseTxt); (*_blobIt)->LinkEndChild(poseKey); @@ -3378,16 +3409,16 @@ void ReduceSDFExtensionSensorTransformReduction( //////////////////////////////////////////////////////////////////////////////// void ReduceSDFExtensionProjectorTransformReduction( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, ignition::math::Pose3d _reductionTransform) { // overwrite (xyz/rpy) if it exists - if ((*_blobIt)->ValueStr() == "projector") + if ( strcmp((*_blobIt)->FirstChildElement()->Name(), "projector") == 0) { // parse it and add/replace the reduction transform // find first instance of xyz and rpy, replace with reduction transform // - // for (TiXmlNode* elIt = (*_blobIt)->FirstChild(); + // for (tinyxml2::XMLNode* elIt = (*_blobIt)->FirstChildElement(); // elIt; elIt = elIt->NextSibling()) // { // std::ostringstream streamIn; @@ -3396,13 +3427,13 @@ void ReduceSDFExtensionProjectorTransformReduction( // } // should read ... and agregate reductionTransform - TiXmlNode* poseKey = (*_blobIt)->FirstChild("pose"); + tinyxml2::XMLNode *poseKey = (*_blobIt)->FirstChildElement("pose"); // read pose and save it // remove the tag for now if (poseKey) { - (*_blobIt)->RemoveChild(poseKey); + (*_blobIt)->DeleteChild(poseKey); } // convert reductionTransform to values @@ -3422,9 +3453,10 @@ void ReduceSDFExtensionProjectorTransformReduction( poseStream << reductionXyz.x << " " << reductionXyz.y << " " << reductionXyz.z << " " << reductionRpy.x << " " << reductionRpy.y << " " << reductionRpy.z; - TiXmlText* poseTxt = new TiXmlText(poseStream.str()); - poseKey = new TiXmlElement("pose"); + auto* doc = (*_blobIt)->GetDocument(); + tinyxml2::XMLText *poseTxt = doc->NewText(poseStream.str().c_str()); + poseKey = doc->NewElement("pose"); poseKey->LinkEndChild(poseTxt); (*_blobIt)->LinkEndChild(poseKey); @@ -3433,31 +3465,33 @@ void ReduceSDFExtensionProjectorTransformReduction( //////////////////////////////////////////////////////////////////////////////// void ReduceSDFExtensionContactSensorFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link) { std::string linkName = _link->name; std::string parentLinkName = _link->getParent()->name; - if ((*_blobIt)->ValueStr() == "sensor") + if ( strcmp((*_blobIt)->FirstChildElement()->Name(), "sensor") == 0) { // parse it and add/replace the reduction transform // find first instance of xyz and rpy, replace with reduction transform - TiXmlNode* contact = (*_blobIt)->FirstChild("contact"); + tinyxml2::XMLNode *contact = (*_blobIt)->FirstChildElement("contact"); if (contact) { - TiXmlNode* collision = contact->FirstChild("collision"); + tinyxml2::XMLNode *collision = contact->FirstChildElement("collision"); if (collision) { if (GetKeyValueAsString(collision->ToElement()) == linkName + g_collisionExt) { - contact->RemoveChild(collision); - TiXmlElement* collisionNameKey = new TiXmlElement("collision"); + contact->DeleteChild(collision); + + auto* doc = contact->GetDocument(); + tinyxml2::XMLElement *collisionNameKey = doc->NewElement("collision"); std::ostringstream collisionNameStream; collisionNameStream << parentLinkName << g_collisionExt << "_" << linkName; - TiXmlText* collisionNameTxt = new TiXmlText( - collisionNameStream.str()); + tinyxml2::XMLText *collisionNameTxt = doc->NewText( + collisionNameStream.str().c_str()); collisionNameKey->LinkEndChild(collisionNameTxt); contact->LinkEndChild(collisionNameKey); } @@ -3471,49 +3505,53 @@ void ReduceSDFExtensionContactSensorFrameReplace( //////////////////////////////////////////////////////////////////////////////// void ReduceSDFExtensionPluginFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link, const std::string &_pluginName, const std::string &_elementName, ignition::math::Pose3d _reductionTransform) { std::string linkName = _link->name; std::string parentLinkName = _link->getParent()->name; - if ((*_blobIt)->ValueStr() == _pluginName) + if ((*_blobIt)->FirstChildElement()->Name() == _pluginName) { // replace element containing _link names to parent link names // find first instance of xyz and rpy, replace with reduction transform - TiXmlNode* elementNode = (*_blobIt)->FirstChild(_elementName); + tinyxml2::XMLNode *elementNode = + (*_blobIt)->FirstChildElement(_elementName.c_str()); if (elementNode) { if (GetKeyValueAsString(elementNode->ToElement()) == linkName) { - (*_blobIt)->RemoveChild(elementNode); - TiXmlElement* bodyNameKey = new TiXmlElement(_elementName); + (*_blobIt)->DeleteChild(elementNode); + auto* doc = elementNode->GetDocument(); + tinyxml2::XMLElement *bodyNameKey = + doc->NewElement(_elementName.c_str()); std::ostringstream bodyNameStream; bodyNameStream << parentLinkName; - TiXmlText* bodyNameTxt = new TiXmlText(bodyNameStream.str()); + tinyxml2::XMLText *bodyNameTxt = + doc->NewText(bodyNameStream.str().c_str()); bodyNameKey->LinkEndChild(bodyNameTxt); (*_blobIt)->LinkEndChild(bodyNameKey); /// @todo update transforms for this sdf plugin too // look for offset transforms, add reduction transform - TiXmlNode* xyzKey = (*_blobIt)->FirstChild("xyzOffset"); + tinyxml2::XMLNode *xyzKey = (*_blobIt)->FirstChildElement("xyzOffset"); if (xyzKey) { urdf::Vector3 v1 = ParseVector3(xyzKey); _reductionTransform.Pos() = ignition::math::Vector3d(v1.x, v1.y, v1.z); // remove xyzOffset and rpyOffset - (*_blobIt)->RemoveChild(xyzKey); + (*_blobIt)->DeleteChild(xyzKey); } - TiXmlNode* rpyKey = (*_blobIt)->FirstChild("rpyOffset"); + tinyxml2::XMLNode *rpyKey = (*_blobIt)->FirstChildElement("rpyOffset"); if (rpyKey) { urdf::Vector3 rpy = ParseVector3(rpyKey, M_PI/180.0); _reductionTransform.Rot() = ignition::math::Quaterniond::EulerToQuaternion(rpy.x, rpy.y, rpy.z); // remove xyzOffset and rpyOffset - (*_blobIt)->RemoveChild(rpyKey); + (*_blobIt)->DeleteChild(rpyKey); } // pass through the parent transform from fixed joint reduction @@ -3521,8 +3559,8 @@ void ReduceSDFExtensionPluginFrameReplace( _link->parent_joint->parent_to_joint_origin_transform); // create new offset xml blocks - xyzKey = new TiXmlElement("xyzOffset"); - rpyKey = new TiXmlElement("rpyOffset"); + xyzKey = doc->NewElement("xyzOffset"); + rpyKey = doc->NewElement("rpyOffset"); // create new offset xml blocks urdf::Vector3 reductionXyz(_reductionTransform.Pos().X(), @@ -3541,8 +3579,8 @@ void ReduceSDFExtensionPluginFrameReplace( rpyStream << reductionRpy.x << " " << reductionRpy.y << " " << reductionRpy.z; - TiXmlText* xyzTxt = new TiXmlText(xyzStream.str()); - TiXmlText* rpyTxt = new TiXmlText(rpyStream.str()); + tinyxml2::XMLText *xyzTxt = doc->NewText(xyzStream.str().c_str()); + tinyxml2::XMLText *rpyTxt = doc->NewText(rpyStream.str().c_str()); xyzKey->LinkEndChild(xyzTxt); rpyKey->LinkEndChild(rpyTxt); @@ -3556,7 +3594,7 @@ void ReduceSDFExtensionPluginFrameReplace( //////////////////////////////////////////////////////////////////////////////// void ReduceSDFExtensionProjectorFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link) { std::string linkName = _link->name; @@ -3566,7 +3604,7 @@ void ReduceSDFExtensionProjectorFrameReplace( // projector plugins // update from MyLinkName/MyProjectorName // to NewLinkName/MyProjectorName - TiXmlNode* projectorElem = (*_blobIt)->FirstChild("projector"); + tinyxml2::XMLNode *projectorElem = (*_blobIt)->FirstChildElement("projector"); { if (projectorElem) { @@ -3589,11 +3627,13 @@ void ReduceSDFExtensionProjectorFrameReplace( projectorName = parentLinkName + "/" + projectorName.substr(pos+1, projectorName.size()); - (*_blobIt)->RemoveChild(projectorElem); - TiXmlElement *bodyNameKey = new TiXmlElement("projector"); + (*_blobIt)->DeleteChild(projectorElem); + auto* doc = projectorElem->GetDocument(); + tinyxml2::XMLElement *bodyNameKey = doc->NewElement("projector"); std::ostringstream bodyNameStream; bodyNameStream << projectorName; - TiXmlText *bodyNameTxt = new TiXmlText(bodyNameStream.str()); + tinyxml2::XMLText *bodyNameTxt = + doc->NewText(bodyNameStream.str().c_str()); bodyNameKey->LinkEndChild(bodyNameTxt); (*_blobIt)->LinkEndChild(bodyNameKey); } @@ -3604,38 +3644,44 @@ void ReduceSDFExtensionProjectorFrameReplace( //////////////////////////////////////////////////////////////////////////////// void ReduceSDFExtensionGripperFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link) { std::string linkName = _link->name; std::string parentLinkName = _link->getParent()->name; - if ((*_blobIt)->ValueStr() == "gripper") + if (strcmp((*_blobIt)->FirstChildElement()->Name(), "gripper") == 0) { - TiXmlNode* gripperLink = (*_blobIt)->FirstChild("gripper_link"); + tinyxml2::XMLNode *gripperLink = + (*_blobIt)->FirstChildElement("gripper_link"); if (gripperLink) { if (GetKeyValueAsString(gripperLink->ToElement()) == linkName) { - (*_blobIt)->RemoveChild(gripperLink); - TiXmlElement* bodyNameKey = new TiXmlElement("gripper_link"); + (*_blobIt)->DeleteChild(gripperLink); + auto* doc = (*_blobIt)->GetDocument(); + tinyxml2::XMLElement *bodyNameKey = doc->NewElement("gripper_link"); std::ostringstream bodyNameStream; bodyNameStream << parentLinkName; - TiXmlText* bodyNameTxt = new TiXmlText(bodyNameStream.str()); + tinyxml2::XMLText *bodyNameTxt = + doc->NewText(bodyNameStream.str().c_str()); bodyNameKey->LinkEndChild(bodyNameTxt); (*_blobIt)->LinkEndChild(bodyNameKey); } } - TiXmlNode* palmLink = (*_blobIt)->FirstChild("palm_link"); + tinyxml2::XMLNode *palmLink = (*_blobIt)->FirstChildElement("palm_link"); if (palmLink) { if (GetKeyValueAsString(palmLink->ToElement()) == linkName) { - (*_blobIt)->RemoveChild(palmLink); - TiXmlElement* bodyNameKey = new TiXmlElement("palm_link"); + (*_blobIt)->DeleteChild(palmLink); + auto* doc = (*_blobIt)->GetDocument(); + tinyxml2::XMLElement *bodyNameKey = + doc->NewElement("palm_link"); std::ostringstream bodyNameStream; bodyNameStream << parentLinkName; - TiXmlText* bodyNameTxt = new TiXmlText(bodyNameStream.str()); + tinyxml2::XMLText *bodyNameTxt = + doc->NewText(bodyNameStream.str().c_str()); bodyNameKey->LinkEndChild(bodyNameTxt); (*_blobIt)->LinkEndChild(bodyNameKey); } @@ -3645,40 +3691,43 @@ void ReduceSDFExtensionGripperFrameReplace( //////////////////////////////////////////////////////////////////////////////// void ReduceSDFExtensionJointFrameReplace( - std::vector::iterator _blobIt, + std::vector::iterator _blobIt, urdf::LinkSharedPtr _link) { std::string linkName = _link->name; std::string parentLinkName = _link->getParent()->name; + auto* doc = (*_blobIt)->GetDocument(); - if ((*_blobIt)->ValueStr() == "joint") + if (strcmp((*_blobIt)->FirstChildElement()->Name(), "joint") == 0) { // parse it and add/replace the reduction transform // find first instance of xyz and rpy, replace with reduction transform - TiXmlNode* parent = (*_blobIt)->FirstChild("parent"); + tinyxml2::XMLNode *parent = (*_blobIt)->FirstChildElement("parent"); if (parent) { if (GetKeyValueAsString(parent->ToElement()) == linkName) { - (*_blobIt)->RemoveChild(parent); - TiXmlElement* parentNameKey = new TiXmlElement("parent"); + (*_blobIt)->DeleteChild(parent); + tinyxml2::XMLElement *parentNameKey = doc->NewElement("parent"); std::ostringstream parentNameStream; parentNameStream << parentLinkName; - TiXmlText* parentNameTxt = new TiXmlText(parentNameStream.str()); + tinyxml2::XMLText *parentNameTxt = + doc->NewText(parentNameStream.str().c_str()); parentNameKey->LinkEndChild(parentNameTxt); (*_blobIt)->LinkEndChild(parentNameKey); } } - TiXmlNode* child = (*_blobIt)->FirstChild("child"); + tinyxml2::XMLNode *child = (*_blobIt)->FirstChildElement("child"); if (child) { if (GetKeyValueAsString(child->ToElement()) == linkName) { - (*_blobIt)->RemoveChild(child); - TiXmlElement* childNameKey = new TiXmlElement("child"); + (*_blobIt)->DeleteChild(child); + tinyxml2::XMLElement *childNameKey = doc->NewElement("child"); std::ostringstream childNameStream; childNameStream << parentLinkName; - TiXmlText* childNameTxt = new TiXmlText(childNameStream.str()); + tinyxml2::XMLText *childNameTxt = + doc->NewText(childNameStream.str().c_str()); childNameKey->LinkEndChild(childNameTxt); (*_blobIt)->LinkEndChild(childNameKey); } diff --git a/src/parser_urdf.hh b/src/parser_urdf.hh index 94dca1f07..8f703169c 100644 --- a/src/parser_urdf.hh +++ b/src/parser_urdf.hh @@ -17,7 +17,7 @@ #ifndef SDFORMAT_URDF2SDF_HH_ #define SDFORMAT_URDF2SDF_HH_ -#include +#include #include #include @@ -46,22 +46,25 @@ namespace sdf public: ~URDF2SDF(); /// \brief convert urdf xml document string to sdf xml document - /// \param[in] _xmlDoc a tinyxml document containing the urdf model - /// \return a tinyxml document containing sdf of the model - public: TiXmlDocument InitModelDoc(TiXmlDocument* _xmlDoc); + /// \param[in] _xmlDoc document containing the urdf model. + /// \param[inout] _sdfXmlDoc document to populate with the sdf model. + public: void InitModelDoc(const tinyxml2::XMLDocument* _xmlDoc, + tinyxml2::XMLDocument *_sdfXmlDoc); /// \brief convert urdf file to sdf xml document - /// \param[in] _urdfStr a string containing filename of the urdf model - /// \return a tinyxml document containing sdf of the model - public: TiXmlDocument InitModelFile(const std::string &_filename); + /// \param[in] _urdfStr a string containing filename of the urdf model. + /// \param[inout] _sdfXmlDoc document to populate with the sdf model. + public: void InitModelFile(const std::string &_filename, + tinyxml2::XMLDocument *_sdfXmlDoc); /// \brief convert urdf string to sdf xml document, with option to enforce /// limits. /// \param[in] _urdfStr a string containing model urdf + /// \param[inout] _sdfXmlDoc document to populate with the sdf model. /// \param[in] _enforceLimits option to enforce joint limits - /// \return a tinyxml document containing sdf of the model - public: TiXmlDocument InitModelString(const std::string &_urdfStr, - bool _enforceLimits = true); + public: void InitModelString(const std::string &_urdfStr, + tinyxml2::XMLDocument *_sdfXmlDoc, + bool _enforceLimits = true); /// \brief Return true if the filename is a URDF model. /// \param[in] _filename File to check. @@ -76,7 +79,7 @@ namespace sdf /// things that do not belong in urdf but should be mapped into sdf /// @todo: do this using sdf definitions, not hard coded stuff - private: void ParseSDFExtension(TiXmlDocument &_urdfXml); + private: void ParseSDFExtension(tinyxml2::XMLDocument &_urdfXml); }; } } diff --git a/src/parser_urdf_TEST.cc b/src/parser_urdf_TEST.cc index 19e194638..c9d5a6ada 100644 --- a/src/parser_urdf_TEST.cc +++ b/src/parser_urdf_TEST.cc @@ -36,10 +36,11 @@ std::string getMinimalUrdfTxt() std::string convertUrdfStrToSdfStr(const std::string &_urdf) { sdf::URDF2SDF parser_; - TiXmlDocument sdf_result = parser_.InitModelString(_urdf); - TiXmlPrinter printer; + tinyxml2::XMLDocument sdf_result; + parser_.InitModelString(_urdf, &sdf_result); + tinyxml2::XMLPrinter printer; sdf_result.Accept(&printer); - return printer.Str(); + return printer.CStr(); } ///////////////////////////////////////////////// @@ -54,9 +55,10 @@ TEST(URDFParser, InitModelDoc_EmptyDoc_NoThrow) { // Suppress deprecation for sdf::URDF2SDF ASSERT_NO_THROW( - TiXmlDocument doc = TiXmlDocument(); + tinyxml2::XMLDocument doc = tinyxml2::XMLDocument(); sdf::URDF2SDF parser_; - TiXmlDocument sdf_result = parser_.InitModelDoc(&doc); + tinyxml2::XMLDocument sdf_result; + parser_.InitModelDoc(&doc, &sdf_result); ); // NOLINT(whitespace/parens) } @@ -65,10 +67,11 @@ TEST(URDFParser, InitModelDoc_BasicModel_NoThrow) { // Suppress deprecation for sdf::URDF2SDF ASSERT_NO_THROW( - TiXmlDocument doc; + tinyxml2::XMLDocument doc; doc.Parse(getMinimalUrdfTxt().c_str()); sdf::URDF2SDF parser_; - TiXmlDocument sdf_result = parser_.InitModelDoc(&doc); + tinyxml2::XMLDocument sdf_result; + parser_.InitModelDoc(&doc, &sdf_result); ); // NOLINT(whitespace/parens) } @@ -76,12 +79,16 @@ TEST(URDFParser, InitModelDoc_BasicModel_NoThrow) TEST(URDFParser, ParseResults_BasicModel_ParseEqualToModel) { // URDF -> SDF - TiXmlDocument doc; + tinyxml2::XMLDocument doc; doc.Parse(getMinimalUrdfTxt().c_str()); sdf::URDF2SDF parser_; - TiXmlDocument sdf_result = parser_.InitModelDoc(&doc); - std::string sdf_result_str; - sdf_result_str << sdf_result; + + tinyxml2::XMLDocument sdf_result; + parser_.InitModelDoc(&doc, &sdf_result); + + tinyxml2::XMLPrinter printer; + sdf_result.Print(&printer); + std::string sdf_result_str = printer.CStr(); // SDF -> SDF std::ostringstream stream; @@ -89,10 +96,12 @@ TEST(URDFParser, ParseResults_BasicModel_ParseEqualToModel) stream << "" << " " << ""; - TiXmlDocument sdf_doc; + tinyxml2::XMLDocument sdf_doc; sdf_doc.Parse(stream.str().c_str()); - std::string sdf_same_result_str; - sdf_same_result_str << sdf_doc; + + tinyxml2::XMLPrinter printer2; + sdf_doc.Print(&printer2); + std::string sdf_same_result_str = printer2.CStr(); ASSERT_EQ(sdf_same_result_str, sdf_result_str); } @@ -105,15 +114,16 @@ TEST(URDFParser, ParseRobotOriginXYZBlank) << " " << " " << ""; - TiXmlDocument doc; + tinyxml2::XMLDocument doc; doc.Parse(stream.str().c_str()); sdf::URDF2SDF parser_; - TiXmlDocument sdf_result = parser_.InitModelDoc(&doc); - TiXmlElement *sdf = sdf_result.FirstChildElement("sdf"); + tinyxml2::XMLDocument sdf_result; + parser_.InitModelDoc(&doc, &sdf_result); + tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement("sdf"); ASSERT_NE(nullptr, sdf); - TiXmlElement *model = sdf->FirstChildElement("model"); + tinyxml2::XMLElement *model = sdf->FirstChildElement("model"); ASSERT_NE(nullptr, model); - TiXmlElement *pose = model->FirstChildElement("pose"); + tinyxml2::XMLElement *pose = model->FirstChildElement("pose"); ASSERT_NE(nullptr, pose); } @@ -125,15 +135,16 @@ TEST(URDFParser, ParseRobotOriginRPYBlank) << " " << " " << ""; - TiXmlDocument doc; + tinyxml2::XMLDocument doc; sdf::URDF2SDF parser_; doc.Parse(stream.str().c_str()); - TiXmlDocument sdf_result = parser_.InitModelDoc(&doc); - TiXmlElement *sdf = sdf_result.FirstChildElement("sdf"); + tinyxml2::XMLDocument sdf_result; + parser_.InitModelDoc(&doc, &sdf_result); + tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement("sdf"); ASSERT_NE(nullptr, sdf); - TiXmlElement *model = sdf->FirstChildElement("model"); + tinyxml2::XMLElement *model = sdf->FirstChildElement("model"); ASSERT_NE(nullptr, model); - TiXmlElement *pose = model->FirstChildElement("pose"); + tinyxml2::XMLElement *pose = model->FirstChildElement("pose"); ASSERT_NE(nullptr, pose); } @@ -158,10 +169,11 @@ TEST(URDFParser, ParseRobotMaterialBlank) << " 0.2" << " " << ""; - TiXmlDocument doc; + tinyxml2::XMLDocument doc; doc.Parse(stream.str().c_str()); sdf::URDF2SDF parser; - auto sdfXml = parser.InitModelDoc(&doc); + tinyxml2::XMLDocument sdfXml; + parser.InitModelDoc(&doc, &sdfXml); auto sdfElem = sdfXml.FirstChildElement("sdf"); ASSERT_NE(nullptr, sdfElem); auto modelElem = sdfElem->FirstChildElement("model"); @@ -199,10 +211,13 @@ TEST(URDFParser, ParseRobotMaterialName) << " Gazebo/Orange" << " " << ""; - TiXmlDocument doc; + tinyxml2::XMLDocument doc; doc.Parse(stream.str().c_str()); sdf::URDF2SDF parser; - auto sdfXml = parser.InitModelDoc(&doc); + + tinyxml2::XMLDocument sdfXml; + parser.InitModelDoc(&doc, &sdfXml); + auto sdfElem = sdfXml.FirstChildElement("sdf"); ASSERT_NE(nullptr, sdfElem); auto modelElem = sdfElem->FirstChildElement("model"); @@ -236,15 +251,16 @@ TEST(URDFParser, ParseRobotOriginInvalidXYZ) << " " << " " << ""; - TiXmlDocument doc; + tinyxml2::XMLDocument doc; sdf::URDF2SDF parser_; doc.Parse(stream.str().c_str()); - TiXmlDocument sdf_result = parser_.InitModelDoc(&doc); - TiXmlElement *sdf = sdf_result.FirstChildElement("sdf"); + tinyxml2::XMLDocument sdf_result; + parser_.InitModelDoc(&doc, &sdf_result); + tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement("sdf"); ASSERT_NE(nullptr, sdf); - TiXmlElement *model = sdf->FirstChildElement("model"); + tinyxml2::XMLElement *model = sdf->FirstChildElement("model"); ASSERT_NE(nullptr, model); - TiXmlElement *pose = model->FirstChildElement("pose"); + tinyxml2::XMLElement *pose = model->FirstChildElement("pose"); ASSERT_NE(nullptr, pose); } @@ -297,25 +313,25 @@ TEST(URDFParser, ParseGazeboLinkFactors) << " " << ""; - TiXmlDocument doc; + tinyxml2::XMLDocument doc; sdf::URDF2SDF parser_; doc.Parse(stream.str().c_str()); - TiXmlDocument sdf_result = parser_.InitModelDoc(&doc); + tinyxml2::XMLDocument sdf_result; + parser_.InitModelDoc(&doc, &sdf_result); - TiXmlElement *tmp = sdf_result.FirstChildElement("sdf"); + tinyxml2::XMLElement *tmp = sdf_result.FirstChildElement("sdf"); ASSERT_NE(nullptr, tmp); unsigned int i; for (i = 0; i < it->second.size() - 1; ++i) { - tmp = tmp->FirstChildElement(it->second[i]); + tmp = tmp->FirstChildElement(it->second[i].c_str()); ASSERT_NE(nullptr, tmp); } // For the last element, check that it is exactly what we expect - EXPECT_EQ(tmp->FirstChild()->ValueStr(), it->second[i]); - + EXPECT_EQ(tmp->FirstChild()->Value(), it->second[i]); parser_.ListSDFExtensions(); parser_.ListSDFExtensions("wheel_left_link"); } @@ -336,10 +352,11 @@ TEST(URDFParser, ParseGazeboInvalidDampingFactor) << " foo" << " " << ""; - TiXmlDocument doc; + tinyxml2::XMLDocument doc; sdf::URDF2SDF parser_; doc.Parse(stream.str().c_str()); - ASSERT_THROW(TiXmlDocument sdf_result = parser_.InitModelDoc(&doc), + tinyxml2::XMLDocument sdf_result; + ASSERT_THROW(parser_.InitModelDoc(&doc, &sdf_result), std::invalid_argument); parser_.ListSDFExtensions(); @@ -408,24 +425,25 @@ TEST(URDFParser, ParseGazeboJointElements) << " " << ""; - TiXmlDocument doc; + tinyxml2::XMLDocument doc; sdf::URDF2SDF parser_; doc.Parse(stream.str().c_str()); - TiXmlDocument sdf_result = parser_.InitModelDoc(&doc); + tinyxml2::XMLDocument sdf_result; + parser_.InitModelDoc(&doc, &sdf_result); - TiXmlElement *tmp = sdf_result.FirstChildElement("sdf"); + tinyxml2::XMLElement *tmp = sdf_result.FirstChildElement("sdf"); ASSERT_NE(nullptr, tmp); unsigned int i; for (i = 0; i < it->second.size() - 1; ++i) { - tmp = tmp->FirstChildElement(it->second[i]); + tmp = tmp->FirstChildElement(it->second[i].c_str()); ASSERT_NE(nullptr, tmp); } // For the last element, check that it is exactly what we expect - EXPECT_EQ(tmp->FirstChild()->ValueStr(), it->second[i]); + EXPECT_STREQ(tmp->FirstChild()->Value(), it->second[i].c_str()); parser_.ListSDFExtensions(); parser_.ListSDFExtensions("head_j0"); @@ -713,7 +731,7 @@ TEST(URDFParser, CheckJointTransform) link1 - + 0 0 0 0 0 0 1 @@ -733,12 +751,12 @@ TEST(URDFParser, CheckJointTransform) link2 1 0 0 - - + + - + 0 0 0 0 0 0 1 @@ -758,12 +776,12 @@ TEST(URDFParser, CheckJointTransform) link3 1 0 0 - - + + - + 0 0 0 0 0 0 1 @@ -799,19 +817,20 @@ TEST(URDFParser, OutputPrecision) )"; sdf::URDF2SDF parser; - TiXmlDocument sdfResult = parser.InitModelString(str); + tinyxml2::XMLDocument sdfResult; + parser.InitModelString(str, &sdfResult); auto root = sdfResult.RootElement(); - auto model = root->FirstChild("model"); + auto model = root->FirstChildElement("model"); ASSERT_NE(nullptr, model); - auto link = model->FirstChild("link"); + auto link = model->FirstChildElement("link"); ASSERT_NE(nullptr, link); - auto inertial = link->FirstChild("inertial"); + auto inertial = link->FirstChildElement("inertial"); ASSERT_NE(nullptr, inertial); - auto pose = inertial->FirstChild("pose"); + auto pose = inertial->FirstChildElement("pose"); ASSERT_NE(nullptr, pose); ASSERT_NE(nullptr, pose->FirstChild()); - std::string poseTxt = pose->FirstChild()->ValueStr(); + std::string poseTxt = pose->FirstChild()->Value(); EXPECT_FALSE(poseTxt.empty()); std::string poseValues[6]; diff --git a/src/urdf/urdf_parser/joint.cpp b/src/urdf/urdf_parser/joint.cpp index 7dcec6581..48765718d 100644 --- a/src/urdf/urdf_parser/joint.cpp +++ b/src/urdf/urdf_parser/joint.cpp @@ -1,13 +1,13 @@ /********************************************************************* * Software Ligcense Agreement (BSD License) -* +* * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. -* +* * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: -* +* * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above @@ -17,7 +17,7 @@ * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. -* +* * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS @@ -40,14 +40,14 @@ #include #include // #include -#include +#include #include namespace urdf{ -bool parsePose(Pose &pose, TiXmlElement* xml); +bool parsePose(Pose &pose, tinyxml2::XMLElement* xml); -bool parseJointDynamics(JointDynamics &jd, TiXmlElement* config) +bool parseJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* config) { jd.clear(); @@ -102,7 +102,7 @@ bool parseJointDynamics(JointDynamics &jd, TiXmlElement* config) } } -bool parseJointLimits(JointLimits &jl, TiXmlElement* config) +bool parseJointLimits(JointLimits &jl, tinyxml2::XMLElement* config) { jl.clear(); @@ -193,7 +193,7 @@ bool parseJointLimits(JointLimits &jl, TiXmlElement* config) return true; } -bool parseJointSafety(JointSafety &js, TiXmlElement* config) +bool parseJointSafety(JointSafety &js, tinyxml2::XMLElement* config) { js.clear(); @@ -287,7 +287,7 @@ bool parseJointSafety(JointSafety &js, TiXmlElement* config) return true; } -bool parseJointCalibration(JointCalibration &jc, TiXmlElement* config) +bool parseJointCalibration(JointCalibration &jc, tinyxml2::XMLElement* config) { jc.clear(); @@ -338,7 +338,7 @@ bool parseJointCalibration(JointCalibration &jc, TiXmlElement* config) return true; } -bool parseJointMimic(JointMimic &jm, TiXmlElement* config) +bool parseJointMimic(JointMimic &jm, tinyxml2::XMLElement* config) { jm.clear(); @@ -351,13 +351,13 @@ bool parseJointMimic(JointMimic &jm, TiXmlElement* config) } else jm.joint_name = joint_name_str; - + // Get mimic multiplier const char* multiplier_str = config->Attribute("multiplier"); if (multiplier_str == NULL) { - jm.multiplier = 1; + jm.multiplier = 1; } else { @@ -375,7 +375,7 @@ bool parseJointMimic(JointMimic &jm, TiXmlElement* config) } } - + // Get mimic offset const char* offset_str = config->Attribute("offset"); if (offset_str == NULL) @@ -401,7 +401,7 @@ bool parseJointMimic(JointMimic &jm, TiXmlElement* config) return true; } -bool parseJoint(Joint &joint, TiXmlElement* config) +bool parseJoint(Joint &joint, tinyxml2::XMLElement* config) { joint.clear(); @@ -414,7 +414,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) joint.name = name; // Get transform from Parent Link to Joint Frame - TiXmlElement *origin_xml = config->FirstChildElement("origin"); + tinyxml2::XMLElement *origin_xml = config->FirstChildElement("origin"); if (!origin_xml) { joint.parent_to_joint_origin_transform.clear(); @@ -429,7 +429,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) } // Get Parent Link - TiXmlElement *parent_xml = config->FirstChildElement("parent"); + tinyxml2::XMLElement *parent_xml = config->FirstChildElement("parent"); if (parent_xml) { const char *pname = parent_xml->Attribute("link"); @@ -443,7 +443,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) } // Get Child Link - TiXmlElement *child_xml = config->FirstChildElement("child"); + tinyxml2::XMLElement *child_xml = config->FirstChildElement("child"); if (child_xml) { const char *pname = child_xml->Attribute("link"); @@ -462,7 +462,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) { return false; } - + std::string type_str = type_char; if (type_str == "planar") joint.type = Joint::PLANAR; @@ -485,7 +485,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) if (joint.type != Joint::FLOATING && joint.type != Joint::FIXED) { // axis - TiXmlElement *axis_xml = config->FirstChildElement("axis"); + tinyxml2::XMLElement *axis_xml = config->FirstChildElement("axis"); if (!axis_xml){ joint.axis = Vector3(1.0, 0.0, 0.0); } @@ -503,7 +503,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) } // Get limit - TiXmlElement *limit_xml = config->FirstChildElement("limit"); + tinyxml2::XMLElement *limit_xml = config->FirstChildElement("limit"); if (limit_xml) { joint.limits.reset(new JointLimits()); @@ -523,7 +523,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) } // Get safety - TiXmlElement *safety_xml = config->FirstChildElement("safety_controller"); + tinyxml2::XMLElement *safety_xml = config->FirstChildElement("safety_controller"); if (safety_xml) { joint.safety.reset(new JointSafety()); @@ -535,7 +535,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) } // Get calibration - TiXmlElement *calibration_xml = config->FirstChildElement("calibration"); + tinyxml2::XMLElement *calibration_xml = config->FirstChildElement("calibration"); if (calibration_xml) { joint.calibration.reset(new JointCalibration()); @@ -547,7 +547,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) } // Get Joint Mimic - TiXmlElement *mimic_xml = config->FirstChildElement("mimic"); + tinyxml2::XMLElement *mimic_xml = config->FirstChildElement("mimic"); if (mimic_xml) { joint.mimic.reset(new JointMimic()); @@ -559,7 +559,7 @@ bool parseJoint(Joint &joint, TiXmlElement* config) } // Get Dynamics - TiXmlElement *prop_xml = config->FirstChildElement("dynamics"); + tinyxml2::XMLElement *prop_xml = config->FirstChildElement("dynamics"); if (prop_xml) { joint.dynamics.reset(new JointDynamics()); @@ -575,71 +575,71 @@ bool parseJoint(Joint &joint, TiXmlElement* config) /* exports */ -bool exportPose(Pose &pose, TiXmlElement* xml); +bool exportPose(Pose &pose, tinyxml2::XMLElement* xml); -bool exportJointDynamics(JointDynamics &jd, TiXmlElement* xml) +bool exportJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* xml) { - TiXmlElement *dynamics_xml = new TiXmlElement("dynamics"); - dynamics_xml->SetAttribute("damping", urdf_export_helpers::values2str(jd.damping) ); - dynamics_xml->SetAttribute("friction", urdf_export_helpers::values2str(jd.friction) ); + tinyxml2::XMLElement *dynamics_xml = xml->GetDocument()->NewElement("dynamics"); + dynamics_xml->SetAttribute("damping", urdf_export_helpers::values2str(jd.damping).c_str() ); + dynamics_xml->SetAttribute("friction", urdf_export_helpers::values2str(jd.friction).c_str() ); xml->LinkEndChild(dynamics_xml); return true; } -bool exportJointLimits(JointLimits &jl, TiXmlElement* xml) +bool exportJointLimits(JointLimits &jl, tinyxml2::XMLElement* xml) { - TiXmlElement *limit_xml = new TiXmlElement("limit"); - limit_xml->SetAttribute("effort", urdf_export_helpers::values2str(jl.effort) ); - limit_xml->SetAttribute("velocity", urdf_export_helpers::values2str(jl.velocity) ); - limit_xml->SetAttribute("lower", urdf_export_helpers::values2str(jl.lower) ); - limit_xml->SetAttribute("upper", urdf_export_helpers::values2str(jl.upper) ); + tinyxml2::XMLElement *limit_xml = xml->GetDocument()->NewElement("limit"); + limit_xml->SetAttribute("effort", urdf_export_helpers::values2str(jl.effort).c_str() ); + limit_xml->SetAttribute("velocity", urdf_export_helpers::values2str(jl.velocity).c_str() ); + limit_xml->SetAttribute("lower", urdf_export_helpers::values2str(jl.lower).c_str() ); + limit_xml->SetAttribute("upper", urdf_export_helpers::values2str(jl.upper).c_str() ); xml->LinkEndChild(limit_xml); return true; } -bool exportJointSafety(JointSafety &js, TiXmlElement* xml) +bool exportJointSafety(JointSafety &js, tinyxml2::XMLElement* xml) { - TiXmlElement *safety_xml = new TiXmlElement("safety_controller"); - safety_xml->SetAttribute("k_position", urdf_export_helpers::values2str(js.k_position) ); - safety_xml->SetAttribute("k_velocity", urdf_export_helpers::values2str(js.k_velocity) ); - safety_xml->SetAttribute("soft_lower_limit", urdf_export_helpers::values2str(js.soft_lower_limit) ); - safety_xml->SetAttribute("soft_upper_limit", urdf_export_helpers::values2str(js.soft_upper_limit) ); + tinyxml2::XMLElement *safety_xml = xml->GetDocument()->NewElement("safety_controller"); + safety_xml->SetAttribute("k_position", urdf_export_helpers::values2str(js.k_position).c_str() ); + safety_xml->SetAttribute("k_velocity", urdf_export_helpers::values2str(js.k_velocity).c_str() ); + safety_xml->SetAttribute("soft_lower_limit", urdf_export_helpers::values2str(js.soft_lower_limit).c_str() ); + safety_xml->SetAttribute("soft_upper_limit", urdf_export_helpers::values2str(js.soft_upper_limit).c_str() ); xml->LinkEndChild(safety_xml); return true; } -bool exportJointCalibration(JointCalibration &jc, TiXmlElement* xml) +bool exportJointCalibration(JointCalibration &jc, tinyxml2::XMLElement* xml) { if (jc.falling || jc.rising) { - TiXmlElement *calibration_xml = new TiXmlElement("calibration"); + tinyxml2::XMLElement *calibration_xml = xml->GetDocument()->NewElement("calibration"); if (jc.falling) - calibration_xml->SetAttribute("falling", urdf_export_helpers::values2str(*jc.falling) ); + calibration_xml->SetAttribute("falling", urdf_export_helpers::values2str(*jc.falling).c_str() ); if (jc.rising) - calibration_xml->SetAttribute("rising", urdf_export_helpers::values2str(*jc.rising) ); + calibration_xml->SetAttribute("rising", urdf_export_helpers::values2str(*jc.rising).c_str() ); //calibration_xml->SetAttribute("reference_position", urdf_export_helpers::values2str(jc.reference_position) ); xml->LinkEndChild(calibration_xml); } return true; } -bool exportJointMimic(JointMimic &jm, TiXmlElement* xml) +bool exportJointMimic(JointMimic &jm, tinyxml2::XMLElement* xml) { if (!jm.joint_name.empty()) { - TiXmlElement *mimic_xml = new TiXmlElement("mimic"); - mimic_xml->SetAttribute("offset", urdf_export_helpers::values2str(jm.offset) ); - mimic_xml->SetAttribute("multiplier", urdf_export_helpers::values2str(jm.multiplier) ); - mimic_xml->SetAttribute("joint", jm.joint_name ); + tinyxml2::XMLElement *mimic_xml = xml->GetDocument()->NewElement("mimic"); + mimic_xml->SetAttribute("offset", urdf_export_helpers::values2str(jm.offset).c_str() ); + mimic_xml->SetAttribute("multiplier", urdf_export_helpers::values2str(jm.multiplier).c_str() ); + mimic_xml->SetAttribute("joint", jm.joint_name.c_str() ); xml->LinkEndChild(mimic_xml); } return true; } -bool exportJoint(Joint &joint, TiXmlElement* xml) +bool exportJoint(Joint &joint, tinyxml2::XMLElement* xml) { - TiXmlElement * joint_xml = new TiXmlElement("joint"); - joint_xml->SetAttribute("name", joint.name); + tinyxml2::XMLElement * joint_xml = xml->GetDocument()->NewElement("joint"); + joint_xml->SetAttribute("name", joint.name.c_str()); if (joint.type == urdf::Joint::PLANAR) joint_xml->SetAttribute("type", "planar"); else if (joint.type == urdf::Joint::FLOATING) @@ -658,18 +658,18 @@ bool exportJoint(Joint &joint, TiXmlElement* xml) exportPose(joint.parent_to_joint_origin_transform, joint_xml); // axis - TiXmlElement * axis_xml = new TiXmlElement("axis"); - axis_xml->SetAttribute("xyz", urdf_export_helpers::values2str(joint.axis)); + tinyxml2::XMLElement * axis_xml = xml->GetDocument()->NewElement("axis"); + axis_xml->SetAttribute("xyz", urdf_export_helpers::values2str(joint.axis).c_str()); joint_xml->LinkEndChild(axis_xml); - // parent - TiXmlElement * parent_xml = new TiXmlElement("parent"); - parent_xml->SetAttribute("link", joint.parent_link_name); + // parent + tinyxml2::XMLElement * parent_xml = xml->GetDocument()->NewElement("parent"); + parent_xml->SetAttribute("link", joint.parent_link_name.c_str()); joint_xml->LinkEndChild(parent_xml); // child - TiXmlElement * child_xml = new TiXmlElement("child"); - child_xml->SetAttribute("link", joint.child_link_name); + tinyxml2::XMLElement * child_xml = xml->GetDocument()->NewElement("child"); + child_xml->SetAttribute("link", joint.child_link_name.c_str()); joint_xml->LinkEndChild(child_xml); if (joint.dynamics) diff --git a/src/urdf/urdf_parser/link.cpp b/src/urdf/urdf_parser/link.cpp index 2860bb8e4..415c4ee5d 100644 --- a/src/urdf/urdf_parser/link.cpp +++ b/src/urdf/urdf_parser/link.cpp @@ -1,13 +1,13 @@ /********************************************************************* * Software License Agreement (BSD License) -* +* * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. -* +* * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: -* +* * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above @@ -17,7 +17,7 @@ * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. -* +* * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS @@ -42,14 +42,14 @@ #include #include #include -#include +#include // #include namespace urdf{ -bool parsePose(Pose &pose, TiXmlElement* xml); +bool parsePose(Pose &pose, tinyxml2::XMLElement* xml); -bool parseMaterial(Material &material, TiXmlElement *config, bool only_name_is_ok) +bool parseMaterial(Material &material, tinyxml2::XMLElement *config, bool only_name_is_ok) { bool has_rgb = false; bool has_filename = false; @@ -60,11 +60,11 @@ bool parseMaterial(Material &material, TiXmlElement *config, bool only_name_is_o { return false; } - + material.name = config->Attribute("name"); // texture - TiXmlElement *t = config->FirstChildElement("texture"); + tinyxml2::XMLElement *t = config->FirstChildElement("texture"); if (t) { if (t->Attribute("filename")) @@ -75,7 +75,7 @@ bool parseMaterial(Material &material, TiXmlElement *config, bool only_name_is_o } // color - TiXmlElement *c = config->FirstChildElement("color"); + tinyxml2::XMLElement *c = config->FirstChildElement("color"); if (c) { if (c->Attribute("rgba")) { @@ -84,7 +84,7 @@ bool parseMaterial(Material &material, TiXmlElement *config, bool only_name_is_o material.color.init(c->Attribute("rgba")); has_rgb = true; } - catch (ParseError &e) { + catch (ParseError &e) { material.color.clear(); } } @@ -100,7 +100,7 @@ bool parseMaterial(Material &material, TiXmlElement *config, bool only_name_is_o } -bool parseSphere(Sphere &s, TiXmlElement *c) +bool parseSphere(Sphere &s, tinyxml2::XMLElement *c) { s.clear(); @@ -126,14 +126,14 @@ bool parseSphere(Sphere &s, TiXmlElement *c) stm << "radius [" << c->Attribute("radius") << "] is out of range: " << e.what(); return false; } - + return true; } -bool parseBox(Box &b, TiXmlElement *c) +bool parseBox(Box &b, tinyxml2::XMLElement *c) { b.clear(); - + b.type = Geometry::BOX; if (!c->Attribute("size")) { @@ -151,7 +151,7 @@ bool parseBox(Box &b, TiXmlElement *c) return true; } -bool parseCylinder(Cylinder &y, TiXmlElement *c) +bool parseCylinder(Cylinder &y, tinyxml2::XMLElement *c) { y.clear(); @@ -199,7 +199,7 @@ bool parseCylinder(Cylinder &y, TiXmlElement *c) } -bool parseMesh(Mesh &m, TiXmlElement *c) +bool parseMesh(Mesh &m, tinyxml2::XMLElement *c) { m.clear(); @@ -226,18 +226,18 @@ bool parseMesh(Mesh &m, TiXmlElement *c) return true; } -GeometrySharedPtr parseGeometry(TiXmlElement *g) +GeometrySharedPtr parseGeometry(tinyxml2::XMLElement *g) { GeometrySharedPtr geom; if (!g) return geom; - TiXmlElement *shape = g->FirstChildElement(); + tinyxml2::XMLElement *shape = g->FirstChildElement(); if (!shape) { return geom; } - std::string type_name = shape->ValueStr(); + std::string type_name = shape->Name(); if (type_name == "sphere") { Sphere *s = new Sphere(); @@ -264,29 +264,29 @@ GeometrySharedPtr parseGeometry(TiXmlElement *g) Mesh *m = new Mesh(); geom.reset(m); if (parseMesh(*m, shape)) - return geom; + return geom; } else { return geom; } - + return GeometrySharedPtr(); } -bool parseInertial(Inertial &i, TiXmlElement *config) +bool parseInertial(Inertial &i, tinyxml2::XMLElement *config) { i.clear(); // Origin - TiXmlElement *o = config->FirstChildElement("origin"); + tinyxml2::XMLElement *o = config->FirstChildElement("origin"); if (o) { if (!parsePose(i.origin, o)) return false; } - TiXmlElement *mass_xml = config->FirstChildElement("mass"); + tinyxml2::XMLElement *mass_xml = config->FirstChildElement("mass"); if (!mass_xml) { return false; @@ -315,7 +315,7 @@ bool parseInertial(Inertial &i, TiXmlElement *config) return false; } - TiXmlElement *inertia_xml = config->FirstChildElement("inertia"); + tinyxml2::XMLElement *inertia_xml = config->FirstChildElement("inertia"); if (!inertia_xml) { return false; @@ -362,19 +362,19 @@ bool parseInertial(Inertial &i, TiXmlElement *config) return true; } -bool parseVisual(Visual &vis, TiXmlElement *config) +bool parseVisual(Visual &vis, tinyxml2::XMLElement *config) { vis.clear(); // Origin - TiXmlElement *o = config->FirstChildElement("origin"); + tinyxml2::XMLElement *o = config->FirstChildElement("origin"); if (o) { if (!parsePose(vis.origin, o)) return false; } // Geometry - TiXmlElement *geom = config->FirstChildElement("geometry"); + tinyxml2::XMLElement *geom = config->FirstChildElement("geometry"); vis.geometry = parseGeometry(geom); if (!vis.geometry) return false; @@ -384,37 +384,37 @@ bool parseVisual(Visual &vis, TiXmlElement *config) vis.name = name_char; // Material - TiXmlElement *mat = config->FirstChildElement("material"); + tinyxml2::XMLElement *mat = config->FirstChildElement("material"); if (mat) { // get material name if (!mat->Attribute("name")) { return false; } vis.material_name = mat->Attribute("name"); - + // try to parse material element in place vis.material.reset(new Material()); if (!parseMaterial(*vis.material, mat, true)) { } } - + return true; } -bool parseCollision(Collision &col, TiXmlElement* config) -{ +bool parseCollision(Collision &col, tinyxml2::XMLElement* config) +{ col.clear(); // Origin - TiXmlElement *o = config->FirstChildElement("origin"); + tinyxml2::XMLElement *o = config->FirstChildElement("origin"); if (o) { if (!parsePose(col.origin, o)) return false; } - + // Geometry - TiXmlElement *geom = config->FirstChildElement("geometry"); + tinyxml2::XMLElement *geom = config->FirstChildElement("geometry"); col.geometry = parseGeometry(geom); if (!col.geometry) return false; @@ -426,9 +426,9 @@ bool parseCollision(Collision &col, TiXmlElement* config) return true; } -bool parseLink(Link &link, TiXmlElement* config) +bool parseLink(Link &link, tinyxml2::XMLElement* config) { - + link.clear(); const char *name_char = config->Attribute("name"); @@ -439,7 +439,7 @@ bool parseLink(Link &link, TiXmlElement* config) link.name = std::string(name_char); // Inertial (optional) - TiXmlElement *i = config->FirstChildElement("inertial"); + tinyxml2::XMLElement *i = config->FirstChildElement("inertial"); if (i) { link.inertial.reset(new Inertial()); @@ -450,7 +450,7 @@ bool parseLink(Link &link, TiXmlElement* config) } // Multiple Visuals (optional) - for (TiXmlElement* vis_xml = config->FirstChildElement("visual"); vis_xml; vis_xml = vis_xml->NextSiblingElement("visual")) + for (tinyxml2::XMLElement* vis_xml = config->FirstChildElement("visual"); vis_xml; vis_xml = vis_xml->NextSiblingElement("visual")) { VisualSharedPtr vis; @@ -470,14 +470,14 @@ bool parseLink(Link &link, TiXmlElement* config) // Assign the first visual to the .visual ptr, if it exists if (!link.visual_array.empty()) link.visual = link.visual_array[0]; - + // Multiple Collisions (optional) - for (TiXmlElement* col_xml = config->FirstChildElement("collision"); col_xml; col_xml = col_xml->NextSiblingElement("collision")) + for (tinyxml2::XMLElement* col_xml = config->FirstChildElement("collision"); col_xml; col_xml = col_xml->NextSiblingElement("collision")) { CollisionSharedPtr col; col.reset(new Collision()); if (parseCollision(*col, col_xml)) - { + { link.collision_array.push_back(col); } else @@ -486,8 +486,8 @@ bool parseLink(Link &link, TiXmlElement* config) return false; } } - - // Collision (optional) + + // Collision (optional) // Assign the first collision to the .collision ptr, if it exists if (!link.collision_array.empty()) link.collision = link.collision_array[0]; @@ -496,67 +496,67 @@ bool parseLink(Link &link, TiXmlElement* config) } /* exports */ -bool exportPose(Pose &pose, TiXmlElement* xml); +bool exportPose(Pose &pose, tinyxml2::XMLElement* xml); -bool exportMaterial(Material &material, TiXmlElement *xml) +bool exportMaterial(Material &material, tinyxml2::XMLElement *xml) { - TiXmlElement *material_xml = new TiXmlElement("material"); - material_xml->SetAttribute("name", material.name); + auto *material_xml = xml->GetDocument()->NewElement("material"); + material_xml->SetAttribute("name", material.name.c_str()); - TiXmlElement* texture = new TiXmlElement("texture"); + auto *texture= xml->GetDocument()->NewElement("texture"); if (!material.texture_filename.empty()) - texture->SetAttribute("filename", material.texture_filename); + texture->SetAttribute("filename", material.texture_filename.c_str()); material_xml->LinkEndChild(texture); - TiXmlElement* color = new TiXmlElement("color"); - color->SetAttribute("rgba", urdf_export_helpers::values2str(material.color)); + auto *color = xml->GetDocument()->NewElement("color"); + color->SetAttribute("rgba", urdf_export_helpers::values2str(material.color).c_str()); material_xml->LinkEndChild(color); xml->LinkEndChild(material_xml); return true; } -bool exportSphere(Sphere &s, TiXmlElement *xml) +bool exportSphere(Sphere &s, tinyxml2::XMLElement *xml) { // e.g. add - TiXmlElement *sphere_xml = new TiXmlElement("sphere"); - sphere_xml->SetAttribute("radius", urdf_export_helpers::values2str(s.radius)); + auto *sphere_xml = xml->GetDocument()->NewElement("sphere"); + sphere_xml->SetAttribute("radius", urdf_export_helpers::values2str(s.radius).c_str()); xml->LinkEndChild(sphere_xml); return true; } -bool exportBox(Box &b, TiXmlElement *xml) +bool exportBox(Box &b, tinyxml2::XMLElement *xml) { // e.g. add - TiXmlElement *box_xml = new TiXmlElement("box"); - box_xml->SetAttribute("size", urdf_export_helpers::values2str(b.dim)); + auto *box_xml = xml->GetDocument()->NewElement("box"); + box_xml->SetAttribute("size", urdf_export_helpers::values2str(b.dim).c_str()); xml->LinkEndChild(box_xml); return true; } -bool exportCylinder(Cylinder &y, TiXmlElement *xml) +bool exportCylinder(Cylinder &y, tinyxml2::XMLElement *xml) { // e.g. add - TiXmlElement *cylinder_xml = new TiXmlElement("cylinder"); - cylinder_xml->SetAttribute("radius", urdf_export_helpers::values2str(y.radius)); - cylinder_xml->SetAttribute("length", urdf_export_helpers::values2str(y.length)); + auto *cylinder_xml = xml->GetDocument()->NewElement("cylinder"); + cylinder_xml->SetAttribute("radius", urdf_export_helpers::values2str(y.radius).c_str()); + cylinder_xml->SetAttribute("length", urdf_export_helpers::values2str(y.length).c_str()); xml->LinkEndChild(cylinder_xml); return true; } -bool exportMesh(Mesh &m, TiXmlElement *xml) +bool exportMesh(Mesh &m, tinyxml2::XMLElement *xml) { // e.g. add - TiXmlElement *mesh_xml = new TiXmlElement("mesh"); + auto *mesh_xml = xml->GetDocument()->NewElement("mesh"); if (!m.filename.empty()) - mesh_xml->SetAttribute("filename", m.filename); - mesh_xml->SetAttribute("scale", urdf_export_helpers::values2str(m.scale)); + mesh_xml->SetAttribute("filename", m.filename.c_str()); + mesh_xml->SetAttribute("scale", urdf_export_helpers::values2str(m.scale).c_str()); xml->LinkEndChild(mesh_xml); return true; } -bool exportGeometry(GeometrySharedPtr &geom, TiXmlElement *xml) +bool exportGeometry(GeometrySharedPtr &geom, tinyxml2::XMLElement *xml) { - TiXmlElement *geometry_xml = new TiXmlElement("geometry"); + auto *geometry_xml= xml->GetDocument()->NewElement("geometry"); if (urdf::dynamic_pointer_cast(geom)) { exportSphere((*(urdf::dynamic_pointer_cast(geom).get())), geometry_xml); @@ -585,36 +585,36 @@ bool exportGeometry(GeometrySharedPtr &geom, TiXmlElement *xml) return true; } -bool exportInertial(Inertial &i, TiXmlElement *xml) +bool exportInertial(Inertial &i, tinyxml2::XMLElement *xml) { // adds // // // // - TiXmlElement *inertial_xml = new TiXmlElement("inertial"); + auto *inertial_xml = xml->GetDocument()->NewElement("inertial"); + auto *mass_xml = xml->GetDocument()->NewElement("mass"); - TiXmlElement *mass_xml = new TiXmlElement("mass"); - mass_xml->SetAttribute("value", urdf_export_helpers::values2str(i.mass)); + mass_xml->SetAttribute("value", urdf_export_helpers::values2str(i.mass).c_str()); inertial_xml->LinkEndChild(mass_xml); exportPose(i.origin, inertial_xml); - TiXmlElement *inertia_xml = new TiXmlElement("inertia"); - inertia_xml->SetAttribute("ixx", urdf_export_helpers::values2str(i.ixx)); - inertia_xml->SetAttribute("ixy", urdf_export_helpers::values2str(i.ixy)); - inertia_xml->SetAttribute("ixz", urdf_export_helpers::values2str(i.ixz)); - inertia_xml->SetAttribute("iyy", urdf_export_helpers::values2str(i.iyy)); - inertia_xml->SetAttribute("iyz", urdf_export_helpers::values2str(i.iyz)); - inertia_xml->SetAttribute("izz", urdf_export_helpers::values2str(i.izz)); + auto *inertia_xml = xml->GetDocument()->NewElement("inertia"); + inertia_xml->SetAttribute("ixx", urdf_export_helpers::values2str(i.ixx).c_str()); + inertia_xml->SetAttribute("ixy", urdf_export_helpers::values2str(i.ixy).c_str()); + inertia_xml->SetAttribute("ixz", urdf_export_helpers::values2str(i.ixz).c_str()); + inertia_xml->SetAttribute("iyy", urdf_export_helpers::values2str(i.iyy).c_str()); + inertia_xml->SetAttribute("iyz", urdf_export_helpers::values2str(i.iyz).c_str()); + inertia_xml->SetAttribute("izz", urdf_export_helpers::values2str(i.izz).c_str()); inertial_xml->LinkEndChild(inertia_xml); xml->LinkEndChild(inertial_xml); - + return true; } -bool exportVisual(Visual &vis, TiXmlElement *xml) +bool exportVisual(Visual &vis, tinyxml2::XMLElement *xml) { // // @@ -623,7 +623,7 @@ bool exportVisual(Visual &vis, TiXmlElement *xml) // // // - TiXmlElement * visual_xml = new TiXmlElement("visual"); + auto *visual_xml = xml->GetDocument()->NewElement("visual"); exportPose(vis.origin, visual_xml); @@ -637,8 +637,8 @@ bool exportVisual(Visual &vis, TiXmlElement *xml) return true; } -bool exportCollision(Collision &col, TiXmlElement* xml) -{ +bool exportCollision(Collision &col, tinyxml2::XMLElement* xml) +{ // // // @@ -646,7 +646,7 @@ bool exportCollision(Collision &col, TiXmlElement* xml) // // // - TiXmlElement * collision_xml = new TiXmlElement("collision"); + auto *collision_xml = xml->GetDocument()->NewElement("collision"); exportPose(col.origin, collision_xml); @@ -657,10 +657,10 @@ bool exportCollision(Collision &col, TiXmlElement* xml) return true; } -bool exportLink(Link &link, TiXmlElement* xml) +bool exportLink(Link &link, tinyxml2::XMLElement* xml) { - TiXmlElement * link_xml = new TiXmlElement("link"); - link_xml->SetAttribute("name", link.name); + auto *link_xml = xml->GetDocument()->NewElement("link"); + link_xml->SetAttribute("name", link.name.c_str()); if (link.inertial) exportInertial(*link.inertial, link_xml); diff --git a/src/urdf/urdf_parser/model.cpp b/src/urdf/urdf_parser/model.cpp index 5337c3242..804c39435 100644 --- a/src/urdf/urdf_parser/model.cpp +++ b/src/urdf/urdf_parser/model.cpp @@ -1,13 +1,13 @@ /********************************************************************* * Software License Agreement (BSD License) -* +* * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. -* +* * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: -* +* * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above @@ -17,7 +17,7 @@ * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. -* +* * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS @@ -42,9 +42,9 @@ namespace urdf{ -bool parseMaterial(Material &material, TiXmlElement *config, bool only_name_is_ok); -bool parseLink(Link &link, TiXmlElement *config); -bool parseJoint(Joint &joint, TiXmlElement *config); +bool parseMaterial(Material &material, tinyxml2::XMLElement *config, bool only_name_is_ok); +bool parseLink(Link &link, tinyxml2::XMLElement *config); +bool parseJoint(Joint &joint, tinyxml2::XMLElement *config); ModelInterfaceSharedPtr parseURDFFile(const std::string &path) { @@ -64,7 +64,7 @@ ModelInterfaceSharedPtr parseURDF(const std::string &xml_string) ModelInterfaceSharedPtr model(new ModelInterface); model->clear(); - TiXmlDocument xml_doc; + tinyxml2::XMLDocument xml_doc; xml_doc.Parse(xml_string.c_str()); if (xml_doc.Error()) { @@ -73,7 +73,7 @@ ModelInterfaceSharedPtr parseURDF(const std::string &xml_string) return model; } - TiXmlElement *robot_xml = xml_doc.FirstChildElement("robot"); + tinyxml2::XMLElement *robot_xml = xml_doc.FirstChildElement("robot"); if (!robot_xml) { model.reset(); @@ -90,7 +90,7 @@ ModelInterfaceSharedPtr parseURDF(const std::string &xml_string) model->name_ = std::string(name); // Get all Material elements - for (TiXmlElement* material_xml = robot_xml->FirstChildElement("material"); material_xml; material_xml = material_xml->NextSiblingElement("material")) + for (tinyxml2::XMLElement* material_xml = robot_xml->FirstChildElement("material"); material_xml; material_xml = material_xml->NextSiblingElement("material")) { MaterialSharedPtr material; material.reset(new Material); @@ -116,7 +116,7 @@ ModelInterfaceSharedPtr parseURDF(const std::string &xml_string) } // Get all Link elements - for (TiXmlElement* link_xml = robot_xml->FirstChildElement("link"); link_xml; link_xml = link_xml->NextSiblingElement("link")) + for (tinyxml2::XMLElement* link_xml = robot_xml->FirstChildElement("link"); link_xml; link_xml = link_xml->NextSiblingElement("link")) { LinkSharedPtr link; link.reset(new Link); @@ -168,7 +168,7 @@ ModelInterfaceSharedPtr parseURDF(const std::string &xml_string) } // Get all Joint elements - for (TiXmlElement* joint_xml = robot_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint")) + for (tinyxml2::XMLElement* joint_xml = robot_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint")) { JointSharedPtr joint; joint.reset(new Joint); @@ -199,7 +199,7 @@ ModelInterfaceSharedPtr parseURDF(const std::string &xml_string) parent_link_tree.clear(); // building tree: name mapping - try + try { model->initTree(parent_link_tree); } @@ -219,19 +219,19 @@ ModelInterfaceSharedPtr parseURDF(const std::string &xml_string) model.reset(); return model; } - + return model; } -bool exportMaterial(Material &material, TiXmlElement *config); -bool exportLink(Link &link, TiXmlElement *config); -bool exportJoint(Joint &joint, TiXmlElement *config); -TiXmlDocument* exportURDF(const ModelInterface &model) +bool exportMaterial(Material &material, tinyxml2::XMLElement *config); +bool exportLink(Link &link, tinyxml2::XMLElement *config); +bool exportJoint(Joint &joint, tinyxml2::XMLElement *config); +tinyxml2::XMLDocument* exportURDF(const ModelInterface &model) { - TiXmlDocument *doc = new TiXmlDocument(); + tinyxml2::XMLDocument *doc = new tinyxml2::XMLDocument(); + tinyxml2::XMLElement *robot = doc->NewElement("robot"); - TiXmlElement *robot = new TiXmlElement("robot"); - robot->SetAttribute("name", model.name_); + robot->SetAttribute("name", model.name_.c_str()); doc->LinkEndChild(robot); @@ -240,20 +240,20 @@ TiXmlDocument* exportURDF(const ModelInterface &model) exportMaterial(*(m->second), robot); } - for (std::map::const_iterator l=model.links_.begin(); l!=model.links_.end(); l++) + for (std::map::const_iterator l=model.links_.begin(); l!=model.links_.end(); l++) { exportLink(*(l->second), robot); } - - for (std::map::const_iterator j=model.joints_.begin(); j!=model.joints_.end(); j++) + + for (std::map::const_iterator j=model.joints_.begin(); j!=model.joints_.end(); j++) { exportJoint(*(j->second), robot); } return doc; } - -TiXmlDocument* exportURDF(ModelInterfaceSharedPtr &model) + +tinyxml2::XMLDocument* exportURDF(ModelInterfaceSharedPtr &model) { return exportURDF(*model); } diff --git a/src/urdf/urdf_parser/pose.cpp b/src/urdf/urdf_parser/pose.cpp index 44998dd32..32207e1be 100644 --- a/src/urdf/urdf_parser/pose.cpp +++ b/src/urdf/urdf_parser/pose.cpp @@ -1,13 +1,13 @@ /********************************************************************* * Software License Agreement (BSD License) -* +* * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. -* +* * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: -* +* * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above @@ -17,7 +17,7 @@ * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. -* +* * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS @@ -40,7 +40,7 @@ #include #include // #include -#include +#include #include namespace urdf_export_helpers { @@ -87,7 +87,7 @@ std::string values2str(double d) namespace urdf{ -bool parsePose(Pose &pose, TiXmlElement* xml) +bool parsePose(Pose &pose, tinyxml2::XMLElement* xml) { pose.clear(); if (xml) @@ -117,13 +117,13 @@ bool parsePose(Pose &pose, TiXmlElement* xml) return true; } -bool exportPose(Pose &pose, TiXmlElement* xml) +bool exportPose(Pose &pose, tinyxml2::XMLElement* xml) { - TiXmlElement *origin = new TiXmlElement("origin"); + tinyxml2::XMLElement *origin = xml->GetDocument()->NewElement("origin"); std::string pose_xyz_str = urdf_export_helpers::values2str(pose.position); std::string pose_rpy_str = urdf_export_helpers::values2str(pose.rotation); - origin->SetAttribute("xyz", pose_xyz_str); - origin->SetAttribute("rpy", pose_rpy_str); + origin->SetAttribute("xyz", pose_xyz_str.c_str()); + origin->SetAttribute("rpy", pose_rpy_str.c_str()); xml->LinkEndChild(origin); return true; } diff --git a/src/urdf/urdf_parser/twist.cpp b/src/urdf/urdf_parser/twist.cpp index af2271326..895d50c4b 100644 --- a/src/urdf/urdf_parser/twist.cpp +++ b/src/urdf/urdf_parser/twist.cpp @@ -39,12 +39,12 @@ #include #include #include -#include +#include //#include namespace urdf{ -bool parseTwist(Twist &twist, TiXmlElement* xml) +bool parseTwist(Twist &twist, tinyxml2::XMLElement* xml) { twist.clear(); if (xml) diff --git a/src/urdf/urdf_parser/urdf_model_state.cpp b/src/urdf/urdf_parser/urdf_model_state.cpp index ddb8e11ea..add84ebe2 100644 --- a/src/urdf/urdf_parser/urdf_model_state.cpp +++ b/src/urdf/urdf_parser/urdf_model_state.cpp @@ -42,12 +42,12 @@ #include #include #include -#include +#include // #include namespace urdf{ -bool parseModelState(ModelState &ms, TiXmlElement* config) +bool parseModelState(ModelState &ms, tinyxml2::XMLElement* config) { ms.clear(); @@ -73,7 +73,7 @@ bool parseModelState(ModelState &ms, TiXmlElement* config) } } - TiXmlElement *joint_state_elem = config->FirstChildElement("joint_state"); + tinyxml2::XMLElement *joint_state_elem = config->FirstChildElement("joint_state"); if (joint_state_elem) { JointStateSharedPtr joint_state; diff --git a/src/urdf/urdf_parser/urdf_parser.h b/src/urdf/urdf_parser/urdf_parser.h index 939a91a54..60fd509f7 100644 --- a/src/urdf/urdf_parser/urdf_parser.h +++ b/src/urdf/urdf_parser/urdf_parser.h @@ -39,7 +39,7 @@ #include #include -#include +#include #include #include #include @@ -60,9 +60,9 @@ namespace urdf{ URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDF(const std::string &xml_string); URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDFFile(const std::string &path); - URDFDOM_DLLAPI TiXmlDocument* exportURDF(ModelInterfaceSharedPtr &model); - URDFDOM_DLLAPI TiXmlDocument* exportURDF(const ModelInterface &model); - URDFDOM_DLLAPI bool parsePose(Pose&, TiXmlElement*); + URDFDOM_DLLAPI tinyxml2::XMLDocument* exportURDF(ModelInterfaceSharedPtr &model); + URDFDOM_DLLAPI tinyxml2::XMLDocument* exportURDF(const ModelInterface &model); + URDFDOM_DLLAPI bool parsePose(Pose&, tinyxml2::XMLElement*); } #endif diff --git a/src/urdf/urdf_parser/urdf_sensor.cpp b/src/urdf/urdf_parser/urdf_sensor.cpp index c87ec0a15..657ac4fdc 100644 --- a/src/urdf/urdf_parser/urdf_sensor.cpp +++ b/src/urdf/urdf_parser/urdf_sensor.cpp @@ -41,19 +41,19 @@ #include #include #include -#include +#include // #include namespace urdf{ -bool parsePose(Pose &pose, TiXmlElement* xml); +bool parsePose(Pose &pose, tinyxml2::XMLElement* xml); -bool parseCamera(Camera &camera, TiXmlElement* config) +bool parseCamera(Camera &camera, tinyxml2::XMLElement* config) { camera.clear(); camera.type = VisualSensor::CAMERA; - TiXmlElement *image = config->FirstChildElement("image"); + tinyxml2::XMLElement *image = config->FirstChildElement("image"); if (image) { const char* width_char = image->Attribute("width"); @@ -177,12 +177,12 @@ bool parseCamera(Camera &camera, TiXmlElement* config) return true; } -bool parseRay(Ray &ray, TiXmlElement* config) +bool parseRay(Ray &ray, tinyxml2::XMLElement* config) { ray.clear(); ray.type = VisualSensor::RAY; - TiXmlElement *horizontal = config->FirstChildElement("horizontal"); + tinyxml2::XMLElement *horizontal = config->FirstChildElement("horizontal"); if (horizontal) { const char* samples_char = horizontal->Attribute("samples"); @@ -254,7 +254,7 @@ bool parseRay(Ray &ray, TiXmlElement* config) } } - TiXmlElement *vertical = config->FirstChildElement("vertical"); + tinyxml2::XMLElement *vertical = config->FirstChildElement("vertical"); if (vertical) { const char* samples_char = vertical->Attribute("samples"); @@ -328,12 +328,12 @@ bool parseRay(Ray &ray, TiXmlElement* config) return false; } -VisualSensorSharedPtr parseVisualSensor(TiXmlElement *g) +VisualSensorSharedPtr parseVisualSensor(tinyxml2::XMLElement *g) { VisualSensorSharedPtr visual_sensor; // get sensor type - TiXmlElement *sensor_xml; + tinyxml2::XMLElement *sensor_xml; if (g->FirstChildElement("camera")) { Camera *camera = new Camera(); @@ -357,7 +357,7 @@ VisualSensorSharedPtr parseVisualSensor(TiXmlElement *g) } -bool parseSensor(Sensor &sensor, TiXmlElement* config) +bool parseSensor(Sensor &sensor, tinyxml2::XMLElement* config) { sensor.clear(); @@ -377,7 +377,7 @@ bool parseSensor(Sensor &sensor, TiXmlElement* config) sensor.parent_link_name = std::string(parent_link_name_char); // parse origin - TiXmlElement *o = config->FirstChildElement("origin"); + tinyxml2::XMLElement *o = config->FirstChildElement("origin"); if (o) { if (!parsePose(sensor.origin, o)) diff --git a/src/urdf/urdf_parser/world.cpp b/src/urdf/urdf_parser/world.cpp index 141074049..c1dcb7d37 100644 --- a/src/urdf/urdf_parser/world.cpp +++ b/src/urdf/urdf_parser/world.cpp @@ -1,13 +1,13 @@ /********************************************************************* * Software License Agreement (BSD License) -* +* * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. -* +* * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: -* +* * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above @@ -17,7 +17,7 @@ * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. -* +* * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS @@ -41,12 +41,12 @@ #include #include #include -#include +#include //#include namespace urdf{ -bool parseWorld(World &/*world*/, TiXmlElement* /*config*/) +bool parseWorld(World &/*world*/, tinyxml2::XMLElement* /*config*/) { // to be implemented @@ -54,10 +54,10 @@ bool parseWorld(World &/*world*/, TiXmlElement* /*config*/) return true; } -bool exportWorld(World &world, TiXmlElement* xml) +bool exportWorld(World &world, tinyxml2::XMLElement* xml) { - TiXmlElement * world_xml = new TiXmlElement("world"); - world_xml->SetAttribute("name", world.name); + tinyxml2::XMLElement * world_xml = xml->GetDocument()->NewElement("world"); + world_xml->SetAttribute("name", world.name.c_str()); // to be implemented // exportModels(*world.models, world_xml); diff --git a/src/urdf/urdf_world/world.h b/src/urdf/urdf_world/world.h index 7b0e8c101..566d08ba3 100644 --- a/src/urdf/urdf_world/world.h +++ b/src/urdf/urdf_world/world.h @@ -73,7 +73,7 @@ #include #include #include -#include +#include #include "urdf_model/model.h" #include "urdf_model/pose.h" @@ -100,7 +100,7 @@ class World std::vector models; - void initXml(TiXmlElement* config); + void initXml(tinyxml2::XMLElement* config); void clear() { diff --git a/src/win/tinyxml/VERSION_2.6.2 b/src/win/tinyxml/VERSION_2.6.2 deleted file mode 100644 index ca466dd3d..000000000 --- a/src/win/tinyxml/VERSION_2.6.2 +++ /dev/null @@ -1,2 +0,0 @@ -with the patch: -https://raw.githubusercontent.com/robotology/yarp/master/extern/tinyxml/patches/entity-encoding.patch diff --git a/src/win/tinyxml/tinystr.cpp b/src/win/tinyxml/tinystr.cpp deleted file mode 100644 index 066576820..000000000 --- a/src/win/tinyxml/tinystr.cpp +++ /dev/null @@ -1,111 +0,0 @@ -/* -www.sourceforge.net/projects/tinyxml - -This software is provided 'as-is', without any express or implied -warranty. In no event will the authors be held liable for any -damages arising from the use of this software. - -Permission is granted to anyone to use this software for any -purpose, including commercial applications, and to alter it and -redistribute it freely, subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must -not claim that you wrote the original software. If you use this -software in a product, an acknowledgment in the product documentation -would be appreciated but is not required. - -2. Altered source versions must be plainly marked as such, and -must not be misrepresented as being the original software. - -3. This notice may not be removed or altered from any source -distribution. -*/ - - -#ifndef TIXML_USE_STL - -#include "tinystr.h" - -// Error value for find primitive -const TiXmlString::size_type TiXmlString::npos = static_cast< TiXmlString::size_type >(-1); - - -// Null rep. -TiXmlString::Rep TiXmlString::nullrep_ = { 0, 0, { '\0' } }; - - -void TiXmlString::reserve (size_type cap) -{ - if (cap > capacity()) - { - TiXmlString tmp; - tmp.init(length(), cap); - memcpy(tmp.start(), data(), length()); - swap(tmp); - } -} - - -TiXmlString& TiXmlString::assign(const char* str, size_type len) -{ - size_type cap = capacity(); - if (len > cap || cap > 3*(len + 8)) - { - TiXmlString tmp; - tmp.init(len); - memcpy(tmp.start(), str, len); - swap(tmp); - } - else - { - memmove(start(), str, len); - set_size(len); - } - return *this; -} - - -TiXmlString& TiXmlString::append(const char* str, size_type len) -{ - size_type newsize = length() + len; - if (newsize > capacity()) - { - reserve (newsize + capacity()); - } - memmove(finish(), str, len); - set_size(newsize); - return *this; -} - - -TiXmlString operator + (const TiXmlString & a, const TiXmlString & b) -{ - TiXmlString tmp; - tmp.reserve(a.length() + b.length()); - tmp += a; - tmp += b; - return tmp; -} - -TiXmlString operator + (const TiXmlString & a, const char* b) -{ - TiXmlString tmp; - TiXmlString::size_type b_len = static_cast( strlen(b) ); - tmp.reserve(a.length() + b_len); - tmp += a; - tmp.append(b, b_len); - return tmp; -} - -TiXmlString operator + (const char* a, const TiXmlString & b) -{ - TiXmlString tmp; - TiXmlString::size_type a_len = static_cast( strlen(a) ); - tmp.reserve(a_len + b.length()); - tmp.append(a, a_len); - tmp += b; - return tmp; -} - - -#endif // TIXML_USE_STL diff --git a/src/win/tinyxml/tinystr.h b/src/win/tinyxml/tinystr.h deleted file mode 100644 index 89cca3341..000000000 --- a/src/win/tinyxml/tinystr.h +++ /dev/null @@ -1,305 +0,0 @@ -/* -www.sourceforge.net/projects/tinyxml - -This software is provided 'as-is', without any express or implied -warranty. In no event will the authors be held liable for any -damages arising from the use of this software. - -Permission is granted to anyone to use this software for any -purpose, including commercial applications, and to alter it and -redistribute it freely, subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must -not claim that you wrote the original software. If you use this -software in a product, an acknowledgment in the product documentation -would be appreciated but is not required. - -2. Altered source versions must be plainly marked as such, and -must not be misrepresented as being the original software. - -3. This notice may not be removed or altered from any source -distribution. -*/ - - -#ifndef TIXML_USE_STL - -#ifndef TIXML_STRING_INCLUDED -#define TIXML_STRING_INCLUDED - -#include -#include - -/* The support for explicit isn't that universal, and it isn't really - required - it is used to check that the TiXmlString class isn't incorrectly - used. Be nice to old compilers and macro it here: -*/ -#if defined(_MSC_VER) && (_MSC_VER >= 1200 ) - // Microsoft visual studio, version 6 and higher. - #define TIXML_EXPLICIT explicit -#elif defined(__GNUC__) && (__GNUC__ >= 3 ) - // GCC version 3 and higher.s - #define TIXML_EXPLICIT explicit -#else - #define TIXML_EXPLICIT -#endif - - -/* - TiXmlString is an emulation of a subset of the std::string template. - Its purpose is to allow compiling TinyXML on compilers with no or poor STL support. - Only the member functions relevant to the TinyXML project have been implemented. - The buffer allocation is made by a simplistic power of 2 like mechanism : if we increase - a string and there's no more room, we allocate a buffer twice as big as we need. -*/ -class TiXmlString -{ - public : - // The size type used - typedef size_t size_type; - - // Error value for find primitive - static const size_type npos; // = -1; - - - // TiXmlString empty constructor - TiXmlString () : rep_(&nullrep_) - { - } - - // TiXmlString copy constructor - TiXmlString ( const TiXmlString & copy) : rep_(0) - { - init(copy.length()); - memcpy(start(), copy.data(), length()); - } - - // TiXmlString constructor, based on a string - TIXML_EXPLICIT TiXmlString ( const char * copy) : rep_(0) - { - init( static_cast( strlen(copy) )); - memcpy(start(), copy, length()); - } - - // TiXmlString constructor, based on a string - TIXML_EXPLICIT TiXmlString ( const char * str, size_type len) : rep_(0) - { - init(len); - memcpy(start(), str, len); - } - - // TiXmlString destructor - ~TiXmlString () - { - quit(); - } - - TiXmlString& operator = (const char * copy) - { - return assign( copy, (size_type)strlen(copy)); - } - - TiXmlString& operator = (const TiXmlString & copy) - { - return assign(copy.start(), copy.length()); - } - - - // += operator. Maps to append - TiXmlString& operator += (const char * suffix) - { - return append(suffix, static_cast( strlen(suffix) )); - } - - // += operator. Maps to append - TiXmlString& operator += (char single) - { - return append(&single, 1); - } - - // += operator. Maps to append - TiXmlString& operator += (const TiXmlString & suffix) - { - return append(suffix.data(), suffix.length()); - } - - - // Convert a TiXmlString into a null-terminated char * - const char * c_str () const { return rep_->str; } - - // Convert a TiXmlString into a char * (need not be null terminated). - const char * data () const { return rep_->str; } - - // Return the length of a TiXmlString - size_type length () const { return rep_->size; } - - // Alias for length() - size_type size () const { return rep_->size; } - - // Checks if a TiXmlString is empty - bool empty () const { return rep_->size == 0; } - - // Return capacity of string - size_type capacity () const { return rep_->capacity; } - - - // single char extraction - const char& at (size_type index) const - { - assert( index < length() ); - return rep_->str[ index ]; - } - - // [] operator - char& operator [] (size_type index) const - { - assert( index < length() ); - return rep_->str[ index ]; - } - - // find a char in a string. Return TiXmlString::npos if not found - size_type find (char lookup) const - { - return find(lookup, 0); - } - - // find a char in a string from an offset. Return TiXmlString::npos if not found - size_type find (char tofind, size_type offset) const - { - if (offset >= length()) return npos; - - for (const char* p = c_str() + offset; *p != '\0'; ++p) - { - if (*p == tofind) return static_cast< size_type >( p - c_str() ); - } - return npos; - } - - void clear () - { - //Lee: - //The original was just too strange, though correct: - // TiXmlString().swap(*this); - //Instead use the quit & re-init: - quit(); - init(0,0); - } - - /* Function to reserve a big amount of data when we know we'll need it. Be aware that this - function DOES NOT clear the content of the TiXmlString if any exists. - */ - void reserve (size_type cap); - - TiXmlString& assign (const char* str, size_type len); - - TiXmlString& append (const char* str, size_type len); - - void swap (TiXmlString& other) - { - Rep* r = rep_; - rep_ = other.rep_; - other.rep_ = r; - } - - private: - - void init(size_type sz) { init(sz, sz); } - void set_size(size_type sz) { rep_->str[ rep_->size = sz ] = '\0'; } - char* start() const { return rep_->str; } - char* finish() const { return rep_->str + rep_->size; } - - struct Rep - { - size_type size, capacity; - char str[1]; - }; - - void init(size_type sz, size_type cap) - { - if (cap) - { - // Lee: the original form: - // rep_ = static_cast(operator new(sizeof(Rep) + cap)); - // doesn't work in some cases of new being overloaded. Switching - // to the normal allocation, although use an 'int' for systems - // that are overly picky about structure alignment. - const size_type bytesNeeded = sizeof(Rep) + cap; - const size_type intsNeeded = ( bytesNeeded + sizeof(int) - 1 ) / sizeof( int ); - rep_ = reinterpret_cast( new int[ intsNeeded ] ); - - rep_->str[ rep_->size = sz ] = '\0'; - rep_->capacity = cap; - } - else - { - rep_ = &nullrep_; - } - } - - void quit() - { - if (rep_ != &nullrep_) - { - // The rep_ is really an array of ints. (see the allocator, above). - // Cast it back before delete, so the compiler won't incorrectly call destructors. - delete [] ( reinterpret_cast( rep_ ) ); - } - } - - Rep * rep_; - static Rep nullrep_; - -} ; - - -inline bool operator == (const TiXmlString & a, const TiXmlString & b) -{ - return ( a.length() == b.length() ) // optimization on some platforms - && ( strcmp(a.c_str(), b.c_str()) == 0 ); // actual compare -} -inline bool operator < (const TiXmlString & a, const TiXmlString & b) -{ - return strcmp(a.c_str(), b.c_str()) < 0; -} - -inline bool operator != (const TiXmlString & a, const TiXmlString & b) { return !(a == b); } -inline bool operator > (const TiXmlString & a, const TiXmlString & b) { return b < a; } -inline bool operator <= (const TiXmlString & a, const TiXmlString & b) { return !(b < a); } -inline bool operator >= (const TiXmlString & a, const TiXmlString & b) { return !(a < b); } - -inline bool operator == (const TiXmlString & a, const char* b) { return strcmp(a.c_str(), b) == 0; } -inline bool operator == (const char* a, const TiXmlString & b) { return b == a; } -inline bool operator != (const TiXmlString & a, const char* b) { return !(a == b); } -inline bool operator != (const char* a, const TiXmlString & b) { return !(b == a); } - -TiXmlString operator + (const TiXmlString & a, const TiXmlString & b); -TiXmlString operator + (const TiXmlString & a, const char* b); -TiXmlString operator + (const char* a, const TiXmlString & b); - - -/* - TiXmlOutStream is an emulation of std::ostream. It is based on TiXmlString. - Only the operators that we need for TinyXML have been developped. -*/ -class TiXmlOutStream : public TiXmlString -{ -public : - - // TiXmlOutStream << operator. - TiXmlOutStream & operator << (const TiXmlString & in) - { - *this += in; - return *this; - } - - // TiXmlOutStream << operator. - TiXmlOutStream & operator << (const char * in) - { - *this += in; - return *this; - } - -} ; - -#endif // TIXML_STRING_INCLUDED -#endif // TIXML_USE_STL diff --git a/src/win/tinyxml/tinyxml.cpp b/src/win/tinyxml/tinyxml.cpp deleted file mode 100644 index 654a51428..000000000 --- a/src/win/tinyxml/tinyxml.cpp +++ /dev/null @@ -1,1861 +0,0 @@ -/* -www.sourceforge.net/projects/tinyxml -Original code by Lee Thomason (www.grinninglizard.com) - -This software is provided 'as-is', without any express or implied -warranty. In no event will the authors be held liable for any -damages arising from the use of this software. - -Permission is granted to anyone to use this software for any -purpose, including commercial applications, and to alter it and -redistribute it freely, subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must -not claim that you wrote the original software. If you use this -software in a product, an acknowledgment in the product documentation -would be appreciated but is not required. - -2. Altered source versions must be plainly marked as such, and -must not be misrepresented as being the original software. - -3. This notice may not be removed or altered from any source -distribution. -*/ - -#include - -#ifdef TIXML_USE_STL -#include -#include -#endif - -#include "tinyxml.h" - -FILE* TiXmlFOpen( const char* filename, const char* mode ); - -bool TiXmlBase::condenseWhiteSpace = true; - -// Microsoft compiler security -FILE* TiXmlFOpen( const char* filename, const char* mode ) -{ - #if defined(_MSC_VER) && (_MSC_VER >= 1400 ) - FILE* fp = 0; - errno_t err = fopen_s( &fp, filename, mode ); - if ( !err && fp ) - return fp; - return 0; - #else - return fopen( filename, mode ); - #endif -} - -void TiXmlBase::EncodeString( const TIXML_STRING& str, TIXML_STRING* outString ) -{ - int i=0; - - while( i<(int)str.length() ) - { - unsigned char c = (unsigned char) str[i]; - - if ( c == '&' ) - { - outString->append( entity[0].str, entity[0].strLength ); - ++i; - } - else if ( c == '<' ) - { - outString->append( entity[1].str, entity[1].strLength ); - ++i; - } - else if ( c == '>' ) - { - outString->append( entity[2].str, entity[2].strLength ); - ++i; - } - else if ( c == '\"' ) - { - outString->append( entity[3].str, entity[3].strLength ); - ++i; - } - else if ( c == '\'' ) - { - outString->append( entity[4].str, entity[4].strLength ); - ++i; - } - else if ( c < 32 ) - { - // Easy pass at non-alpha/numeric/symbol - // Below 32 is symbolic. - char buf[ 32 ]; - - #if defined(TIXML_SNPRINTF) - TIXML_SNPRINTF( buf, sizeof(buf), "&#x%02X;", (unsigned) ( c & 0xff ) ); - #else - sprintf( buf, "&#x%02X;", (unsigned) ( c & 0xff ) ); - #endif - - //*ME: warning C4267: convert 'size_t' to 'int' - //*ME: Int-Cast to make compiler happy ... - outString->append( buf, (int)strlen( buf ) ); - ++i; - } - else - { - //char realc = (char) c; - //outString->append( &realc, 1 ); - *outString += (char) c; // somewhat more efficient function call. - ++i; - } - } -} - - -TiXmlNode::TiXmlNode( NodeType _type ) : TiXmlBase() -{ - parent = 0; - type = _type; - firstChild = 0; - lastChild = 0; - prev = 0; - next = 0; -} - - -TiXmlNode::~TiXmlNode() -{ - TiXmlNode* node = firstChild; - TiXmlNode* temp = 0; - - while ( node ) - { - temp = node; - node = node->next; - delete temp; - } -} - - -void TiXmlNode::CopyTo( TiXmlNode* target ) const -{ - target->SetValue (value.c_str() ); - target->userData = userData; - target->location = location; -} - - -void TiXmlNode::Clear() -{ - TiXmlNode* node = firstChild; - TiXmlNode* temp = 0; - - while ( node ) - { - temp = node; - node = node->next; - delete temp; - } - - firstChild = 0; - lastChild = 0; -} - - -TiXmlNode* TiXmlNode::LinkEndChild( TiXmlNode* node ) -{ - assert( node->parent == 0 || node->parent == this ); - assert( node->GetDocument() == 0 || node->GetDocument() == this->GetDocument() ); - - if ( node->Type() == TiXmlNode::TINYXML_DOCUMENT ) - { - delete node; - if ( GetDocument() ) - GetDocument()->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return 0; - } - - node->parent = this; - - node->prev = lastChild; - node->next = 0; - - if ( lastChild ) - lastChild->next = node; - else - firstChild = node; // it was an empty list. - - lastChild = node; - return node; -} - - -TiXmlNode* TiXmlNode::InsertEndChild( const TiXmlNode& addThis ) -{ - if ( addThis.Type() == TiXmlNode::TINYXML_DOCUMENT ) - { - if ( GetDocument() ) - GetDocument()->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return 0; - } - TiXmlNode* node = addThis.Clone(); - if ( !node ) - return 0; - - return LinkEndChild( node ); -} - - -TiXmlNode* TiXmlNode::InsertBeforeChild( TiXmlNode* beforeThis, const TiXmlNode& addThis ) -{ - if ( !beforeThis || beforeThis->parent != this ) { - return 0; - } - if ( addThis.Type() == TiXmlNode::TINYXML_DOCUMENT ) - { - if ( GetDocument() ) - GetDocument()->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return 0; - } - - TiXmlNode* node = addThis.Clone(); - if ( !node ) - return 0; - node->parent = this; - - node->next = beforeThis; - node->prev = beforeThis->prev; - if ( beforeThis->prev ) - { - beforeThis->prev->next = node; - } - else - { - assert( firstChild == beforeThis ); - firstChild = node; - } - beforeThis->prev = node; - return node; -} - - -TiXmlNode* TiXmlNode::InsertAfterChild( TiXmlNode* afterThis, const TiXmlNode& addThis ) -{ - if ( !afterThis || afterThis->parent != this ) { - return 0; - } - if ( addThis.Type() == TiXmlNode::TINYXML_DOCUMENT ) - { - if ( GetDocument() ) - GetDocument()->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return 0; - } - - TiXmlNode* node = addThis.Clone(); - if ( !node ) - return 0; - node->parent = this; - - node->prev = afterThis; - node->next = afterThis->next; - if ( afterThis->next ) - { - afterThis->next->prev = node; - } - else - { - assert( lastChild == afterThis ); - lastChild = node; - } - afterThis->next = node; - return node; -} - - -TiXmlNode* TiXmlNode::ReplaceChild( TiXmlNode* replaceThis, const TiXmlNode& withThis ) -{ - if ( !replaceThis ) - return 0; - - if ( replaceThis->parent != this ) - return 0; - - if ( withThis.ToDocument() ) { - // A document can never be a child. Thanks to Noam. - TiXmlDocument* document = GetDocument(); - if ( document ) - document->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return 0; - } - - TiXmlNode* node = withThis.Clone(); - if ( !node ) - return 0; - - node->next = replaceThis->next; - node->prev = replaceThis->prev; - - if ( replaceThis->next ) - replaceThis->next->prev = node; - else - lastChild = node; - - if ( replaceThis->prev ) - replaceThis->prev->next = node; - else - firstChild = node; - - delete replaceThis; - node->parent = this; - return node; -} - - -bool TiXmlNode::RemoveChild( TiXmlNode* removeThis ) -{ - if ( !removeThis ) { - return false; - } - - if ( removeThis->parent != this ) - { - assert( 0 ); - return false; - } - - if ( removeThis->next ) - removeThis->next->prev = removeThis->prev; - else - lastChild = removeThis->prev; - - if ( removeThis->prev ) - removeThis->prev->next = removeThis->next; - else - firstChild = removeThis->next; - - delete removeThis; - return true; -} - -const TiXmlNode* TiXmlNode::FirstChild( const char * _value ) const -{ - const TiXmlNode* node; - for ( node = firstChild; node; node = node->next ) - { - if ( strcmp( node->Value(), _value ) == 0 ) - return node; - } - return 0; -} - - -const TiXmlNode* TiXmlNode::LastChild( const char * _value ) const -{ - const TiXmlNode* node; - for ( node = lastChild; node; node = node->prev ) - { - if ( strcmp( node->Value(), _value ) == 0 ) - return node; - } - return 0; -} - - -const TiXmlNode* TiXmlNode::IterateChildren( const TiXmlNode* previous ) const -{ - if ( !previous ) - { - return FirstChild(); - } - else - { - assert( previous->parent == this ); - return previous->NextSibling(); - } -} - - -const TiXmlNode* TiXmlNode::IterateChildren( const char * val, const TiXmlNode* previous ) const -{ - if ( !previous ) - { - return FirstChild( val ); - } - else - { - assert( previous->parent == this ); - return previous->NextSibling( val ); - } -} - - -const TiXmlNode* TiXmlNode::NextSibling( const char * _value ) const -{ - const TiXmlNode* node; - for ( node = next; node; node = node->next ) - { - if ( strcmp( node->Value(), _value ) == 0 ) - return node; - } - return 0; -} - - -const TiXmlNode* TiXmlNode::PreviousSibling( const char * _value ) const -{ - const TiXmlNode* node; - for ( node = prev; node; node = node->prev ) - { - if ( strcmp( node->Value(), _value ) == 0 ) - return node; - } - return 0; -} - - -void TiXmlElement::RemoveAttribute( const char * name ) -{ - #ifdef TIXML_USE_STL - TIXML_STRING str( name ); - TiXmlAttribute* node = attributeSet.Find( str ); - #else - TiXmlAttribute* node = attributeSet.Find( name ); - #endif - if ( node ) - { - attributeSet.Remove( node ); - delete node; - } -} - -const TiXmlElement* TiXmlNode::FirstChildElement() const -{ - const TiXmlNode* node; - - for ( node = FirstChild(); - node; - node = node->NextSibling() ) - { - if ( node->ToElement() ) - return node->ToElement(); - } - return 0; -} - - -const TiXmlElement* TiXmlNode::FirstChildElement( const char * _value ) const -{ - const TiXmlNode* node; - - for ( node = FirstChild( _value ); - node; - node = node->NextSibling( _value ) ) - { - if ( node->ToElement() ) - return node->ToElement(); - } - return 0; -} - - -const TiXmlElement* TiXmlNode::NextSiblingElement() const -{ - const TiXmlNode* node; - - for ( node = NextSibling(); - node; - node = node->NextSibling() ) - { - if ( node->ToElement() ) - return node->ToElement(); - } - return 0; -} - - -const TiXmlElement* TiXmlNode::NextSiblingElement( const char * _value ) const -{ - const TiXmlNode* node; - - for ( node = NextSibling( _value ); - node; - node = node->NextSibling( _value ) ) - { - if ( node->ToElement() ) - return node->ToElement(); - } - return 0; -} - - -const TiXmlDocument* TiXmlNode::GetDocument() const -{ - const TiXmlNode* node; - - for( node = this; node; node = node->parent ) - { - if ( node->ToDocument() ) - return node->ToDocument(); - } - return 0; -} - - -TiXmlElement::TiXmlElement (const char * _value) - : TiXmlNode( TiXmlNode::TINYXML_ELEMENT ) -{ - firstChild = lastChild = 0; - value = _value; -} - - -#ifdef TIXML_USE_STL -TiXmlElement::TiXmlElement( const std::string& _value ) - : TiXmlNode( TiXmlNode::TINYXML_ELEMENT ) -{ - firstChild = lastChild = 0; - value = _value; -} -#endif - - -TiXmlElement::TiXmlElement( const TiXmlElement& copy) - : TiXmlNode( TiXmlNode::TINYXML_ELEMENT ) -{ - firstChild = lastChild = 0; - copy.CopyTo( this ); -} - - -TiXmlElement& TiXmlElement::operator=( const TiXmlElement& base ) -{ - ClearThis(); - base.CopyTo( this ); - return *this; -} - - -TiXmlElement::~TiXmlElement() -{ - ClearThis(); -} - - -void TiXmlElement::ClearThis() -{ - Clear(); - while( attributeSet.First() ) - { - TiXmlAttribute* node = attributeSet.First(); - attributeSet.Remove( node ); - delete node; - } -} - - -const char* TiXmlElement::Attribute( const char* name ) const -{ - const TiXmlAttribute* node = attributeSet.Find( name ); - if ( node ) - return node->Value(); - return 0; -} - - -#ifdef TIXML_USE_STL -const std::string* TiXmlElement::Attribute( const std::string& name ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - if ( attrib ) - return &attrib->ValueStr(); - return 0; -} -#endif - - -const char* TiXmlElement::Attribute( const char* name, int* i ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - const char* result = 0; - - if ( attrib ) { - result = attrib->Value(); - if ( i ) { - attrib->QueryIntValue( i ); - } - } - return result; -} - - -#ifdef TIXML_USE_STL -const std::string* TiXmlElement::Attribute( const std::string& name, int* i ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - const std::string* result = 0; - - if ( attrib ) { - result = &attrib->ValueStr(); - if ( i ) { - attrib->QueryIntValue( i ); - } - } - return result; -} -#endif - - -const char* TiXmlElement::Attribute( const char* name, double* d ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - const char* result = 0; - - if ( attrib ) { - result = attrib->Value(); - if ( d ) { - attrib->QueryDoubleValue( d ); - } - } - return result; -} - - -#ifdef TIXML_USE_STL -const std::string* TiXmlElement::Attribute( const std::string& name, double* d ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - const std::string* result = 0; - - if ( attrib ) { - result = &attrib->ValueStr(); - if ( d ) { - attrib->QueryDoubleValue( d ); - } - } - return result; -} -#endif - - -int TiXmlElement::QueryIntAttribute( const char* name, int* ival ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - if ( !attrib ) - return TIXML_NO_ATTRIBUTE; - return attrib->QueryIntValue( ival ); -} - -int TiXmlElement::QueryUnsignedAttribute( const char* name, unsigned* _value ) const -{ - const TiXmlAttribute* node = attributeSet.Find( name ); - if ( !node ) - return TIXML_NO_ATTRIBUTE; - - int ival = 0; - int result = node->QueryIntValue( &ival ); - *_value = (unsigned)ival; - return result; -} - -int TiXmlElement::QueryBoolAttribute( const char* name, bool* bval ) const -{ - const TiXmlAttribute* node = attributeSet.Find( name ); - if ( !node ) - return TIXML_NO_ATTRIBUTE; - - int result = TIXML_WRONG_TYPE; - if ( StringEqual( node->Value(), "true", true, TIXML_ENCODING_UNKNOWN ) - || StringEqual( node->Value(), "yes", true, TIXML_ENCODING_UNKNOWN ) - || StringEqual( node->Value(), "1", true, TIXML_ENCODING_UNKNOWN ) ) - { - *bval = true; - result = TIXML_SUCCESS; - } - else if ( StringEqual( node->Value(), "false", true, TIXML_ENCODING_UNKNOWN ) - || StringEqual( node->Value(), "no", true, TIXML_ENCODING_UNKNOWN ) - || StringEqual( node->Value(), "0", true, TIXML_ENCODING_UNKNOWN ) ) - { - *bval = false; - result = TIXML_SUCCESS; - } - return result; -} - - - -#ifdef TIXML_USE_STL -int TiXmlElement::QueryIntAttribute( const std::string& name, int* ival ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - if ( !attrib ) - return TIXML_NO_ATTRIBUTE; - return attrib->QueryIntValue( ival ); -} -#endif - - -int TiXmlElement::QueryDoubleAttribute( const char* name, double* dval ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - if ( !attrib ) - return TIXML_NO_ATTRIBUTE; - return attrib->QueryDoubleValue( dval ); -} - - -#ifdef TIXML_USE_STL -int TiXmlElement::QueryDoubleAttribute( const std::string& name, double* dval ) const -{ - const TiXmlAttribute* attrib = attributeSet.Find( name ); - if ( !attrib ) - return TIXML_NO_ATTRIBUTE; - return attrib->QueryDoubleValue( dval ); -} -#endif - - -void TiXmlElement::SetAttribute( const char * name, int val ) -{ - TiXmlAttribute* attrib = attributeSet.FindOrCreate( name ); - if ( attrib ) { - attrib->SetIntValue( val ); - } -} - - -#ifdef TIXML_USE_STL -void TiXmlElement::SetAttribute( const std::string& name, int val ) -{ - TiXmlAttribute* attrib = attributeSet.FindOrCreate( name ); - if ( attrib ) { - attrib->SetIntValue( val ); - } -} -#endif - - -void TiXmlElement::SetDoubleAttribute( const char * name, double val ) -{ - TiXmlAttribute* attrib = attributeSet.FindOrCreate( name ); - if ( attrib ) { - attrib->SetDoubleValue( val ); - } -} - - -#ifdef TIXML_USE_STL -void TiXmlElement::SetDoubleAttribute( const std::string& name, double val ) -{ - TiXmlAttribute* attrib = attributeSet.FindOrCreate( name ); - if ( attrib ) { - attrib->SetDoubleValue( val ); - } -} -#endif - - -void TiXmlElement::SetAttribute( const char * cname, const char * cvalue ) -{ - TiXmlAttribute* attrib = attributeSet.FindOrCreate( cname ); - if ( attrib ) { - attrib->SetValue( cvalue ); - } -} - - -#ifdef TIXML_USE_STL -void TiXmlElement::SetAttribute( const std::string& _name, const std::string& _value ) -{ - TiXmlAttribute* attrib = attributeSet.FindOrCreate( _name ); - if ( attrib ) { - attrib->SetValue( _value ); - } -} -#endif - - -void TiXmlElement::Print( FILE* cfile, int depth ) const -{ - int i; - assert( cfile ); - for ( i=0; iNext() ) - { - fprintf( cfile, " " ); - attrib->Print( cfile, depth ); - } - - // There are 3 different formatting approaches: - // 1) An element without children is printed as a node - // 2) An element with only a text child is printed as text - // 3) An element with children is printed on multiple lines. - TiXmlNode* node; - if ( !firstChild ) - { - fprintf( cfile, " />" ); - } - else if ( firstChild == lastChild && firstChild->ToText() ) - { - fprintf( cfile, ">" ); - firstChild->Print( cfile, depth + 1 ); - fprintf( cfile, "", value.c_str() ); - } - else - { - fprintf( cfile, ">" ); - - for ( node = firstChild; node; node=node->NextSibling() ) - { - if ( !node->ToText() ) - { - fprintf( cfile, "\n" ); - } - node->Print( cfile, depth+1 ); - } - fprintf( cfile, "\n" ); - for( i=0; i", value.c_str() ); - } -} - - -void TiXmlElement::CopyTo( TiXmlElement* target ) const -{ - // superclass: - TiXmlNode::CopyTo( target ); - - // Element class: - // Clone the attributes, then clone the children. - const TiXmlAttribute* attribute = 0; - for( attribute = attributeSet.First(); - attribute; - attribute = attribute->Next() ) - { - target->SetAttribute( attribute->Name(), attribute->Value() ); - } - - TiXmlNode* node = 0; - for ( node = firstChild; node; node = node->NextSibling() ) - { - target->LinkEndChild( node->Clone() ); - } -} - -bool TiXmlElement::Accept( TiXmlVisitor* visitor ) const -{ - if ( visitor->VisitEnter( *this, attributeSet.First() ) ) - { - for ( const TiXmlNode* node=FirstChild(); node; node=node->NextSibling() ) - { - if ( !node->Accept( visitor ) ) - break; - } - } - return visitor->VisitExit( *this ); -} - - -TiXmlNode* TiXmlElement::Clone() const -{ - TiXmlElement* clone = new TiXmlElement( Value() ); - if ( !clone ) - return 0; - - CopyTo( clone ); - return clone; -} - - -const char* TiXmlElement::GetText() const -{ - const TiXmlNode* child = this->FirstChild(); - if ( child ) { - const TiXmlText* childText = child->ToText(); - if ( childText ) { - return childText->Value(); - } - } - return 0; -} - - -TiXmlDocument::TiXmlDocument() : TiXmlNode( TiXmlNode::TINYXML_DOCUMENT ) -{ - tabsize = 4; - useMicrosoftBOM = false; - ClearError(); -} - -TiXmlDocument::TiXmlDocument( const char * documentName ) : TiXmlNode( TiXmlNode::TINYXML_DOCUMENT ) -{ - tabsize = 4; - useMicrosoftBOM = false; - value = documentName; - ClearError(); -} - - -#ifdef TIXML_USE_STL -TiXmlDocument::TiXmlDocument( const std::string& documentName ) : TiXmlNode( TiXmlNode::TINYXML_DOCUMENT ) -{ - tabsize = 4; - useMicrosoftBOM = false; - value = documentName; - ClearError(); -} -#endif - - -TiXmlDocument::TiXmlDocument( const TiXmlDocument& copy ) : TiXmlNode( TiXmlNode::TINYXML_DOCUMENT ) -{ - copy.CopyTo( this ); -} - - -TiXmlDocument& TiXmlDocument::operator=( const TiXmlDocument& copy ) -{ - Clear(); - copy.CopyTo( this ); - return *this; -} - - -bool TiXmlDocument::LoadFile( TiXmlEncoding encoding ) -{ - return LoadFile( Value(), encoding ); -} - - -bool TiXmlDocument::SaveFile() const -{ - return SaveFile( Value() ); -} - -bool TiXmlDocument::LoadFile( const char* _filename, TiXmlEncoding encoding ) -{ - TIXML_STRING filename( _filename ); - value = filename; - - // reading in binary mode so that tinyxml can normalize the EOL - FILE* file = TiXmlFOpen( value.c_str (), "rb" ); - - if ( file ) - { - bool result = LoadFile( file, encoding ); - fclose( file ); - return result; - } - else - { - SetError( TIXML_ERROR_OPENING_FILE, 0, 0, TIXML_ENCODING_UNKNOWN ); - return false; - } -} - -bool TiXmlDocument::LoadFile( FILE* file, TiXmlEncoding encoding ) -{ - if ( !file ) - { - SetError( TIXML_ERROR_OPENING_FILE, 0, 0, TIXML_ENCODING_UNKNOWN ); - return false; - } - - // Delete the existing data: - Clear(); - location.Clear(); - - // Get the file size, so we can pre-allocate the string. HUGE speed impact. - long length = 0; - fseek( file, 0, SEEK_END ); - length = ftell( file ); - fseek( file, 0, SEEK_SET ); - - // Strange case, but good to handle up front. - if ( length <= 0 ) - { - SetError( TIXML_ERROR_DOCUMENT_EMPTY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return false; - } - - // Subtle bug here. TinyXml did use fgets. But from the XML spec: - // 2.11 End-of-Line Handling - // - // - // ...the XML processor MUST behave as if it normalized all line breaks in external - // parsed entities (including the document entity) on input, before parsing, by translating - // both the two-character sequence #xD #xA and any #xD that is not followed by #xA to - // a single #xA character. - // - // - // It is not clear fgets does that, and certainly isn't clear it works cross platform. - // Generally, you expect fgets to translate from the convention of the OS to the c/unix - // convention, and not work generally. - - /* - while( fgets( buf, sizeof(buf), file ) ) - { - data += buf; - } - */ - - char* buf = new char[ length+1 ]; - buf[0] = 0; - - if ( fread( buf, length, 1, file ) != 1 ) { - delete [] buf; - SetError( TIXML_ERROR_OPENING_FILE, 0, 0, TIXML_ENCODING_UNKNOWN ); - return false; - } - - // Process the buffer in place to normalize new lines. (See comment above.) - // Copies from the 'p' to 'q' pointer, where p can advance faster if - // a newline-carriage return is hit. - // - // Wikipedia: - // Systems based on ASCII or a compatible character set use either LF (Line feed, '\n', 0x0A, 10 in decimal) or - // CR (Carriage return, '\r', 0x0D, 13 in decimal) individually, or CR followed by LF (CR+LF, 0x0D 0x0A)... - // * LF: Multics, Unix and Unix-like systems (GNU/Linux, AIX, Xenix, Mac OS X, FreeBSD, etc.), BeOS, Amiga, RISC OS, and others - // * CR+LF: DEC RT-11 and most other early non-Unix, non-IBM OSes, CP/M, MP/M, DOS, OS/2, Microsoft Windows, Symbian OS - // * CR: Commodore 8-bit machines, Apple II family, Mac OS up to version 9 and OS-9 - - const char* p = buf; // the read head - char* q = buf; // the write head - const char CR = 0x0d; - const char LF = 0x0a; - - buf[length] = 0; - while( *p ) { - assert( p < (buf+length) ); - assert( q <= (buf+length) ); - assert( q <= p ); - - if ( *p == CR ) { - *q++ = LF; - p++; - if ( *p == LF ) { // check for CR+LF (and skip LF) - p++; - } - } - else { - *q++ = *p++; - } - } - assert( q <= (buf+length) ); - *q = 0; - - Parse( buf, 0, encoding ); - - delete [] buf; - return !Error(); -} - - -bool TiXmlDocument::SaveFile( const char * filename ) const -{ - // The old c stuff lives on... - FILE* fp = TiXmlFOpen( filename, "w" ); - if ( fp ) - { - bool result = SaveFile( fp ); - fclose( fp ); - return result; - } - return false; -} - - -bool TiXmlDocument::SaveFile( FILE* fp ) const -{ - if ( useMicrosoftBOM ) - { - const unsigned char TIXML_UTF_LEAD_0 = 0xefU; - const unsigned char TIXML_UTF_LEAD_1 = 0xbbU; - const unsigned char TIXML_UTF_LEAD_2 = 0xbfU; - - fputc( TIXML_UTF_LEAD_0, fp ); - fputc( TIXML_UTF_LEAD_1, fp ); - fputc( TIXML_UTF_LEAD_2, fp ); - } - Print( fp, 0 ); - return (ferror(fp) == 0); -} - - -void TiXmlDocument::CopyTo( TiXmlDocument* target ) const -{ - TiXmlNode::CopyTo( target ); - - target->error = error; - target->errorId = errorId; - target->errorDesc = errorDesc; - target->tabsize = tabsize; - target->errorLocation = errorLocation; - target->useMicrosoftBOM = useMicrosoftBOM; - - TiXmlNode* node = 0; - for ( node = firstChild; node; node = node->NextSibling() ) - { - target->LinkEndChild( node->Clone() ); - } -} - - -TiXmlNode* TiXmlDocument::Clone() const -{ - TiXmlDocument* clone = new TiXmlDocument(); - if ( !clone ) - return 0; - - CopyTo( clone ); - return clone; -} - - -void TiXmlDocument::Print( FILE* cfile, int depth ) const -{ - assert( cfile ); - for ( const TiXmlNode* node=FirstChild(); node; node=node->NextSibling() ) - { - node->Print( cfile, depth ); - fprintf( cfile, "\n" ); - } -} - - -bool TiXmlDocument::Accept( TiXmlVisitor* visitor ) const -{ - if ( visitor->VisitEnter( *this ) ) - { - for ( const TiXmlNode* node=FirstChild(); node; node=node->NextSibling() ) - { - if ( !node->Accept( visitor ) ) - break; - } - } - return visitor->VisitExit( *this ); -} - - -const TiXmlAttribute* TiXmlAttribute::Next() const -{ - // We are using knowledge of the sentinel. The sentinel - // have a value or name. - if ( next->value.empty() && next->name.empty() ) - return 0; - return next; -} - -/* -TiXmlAttribute* TiXmlAttribute::Next() -{ - // We are using knowledge of the sentinel. The sentinel - // have a value or name. - if ( next->value.empty() && next->name.empty() ) - return 0; - return next; -} -*/ - -const TiXmlAttribute* TiXmlAttribute::Previous() const -{ - // We are using knowledge of the sentinel. The sentinel - // have a value or name. - if ( prev->value.empty() && prev->name.empty() ) - return 0; - return prev; -} - -/* -TiXmlAttribute* TiXmlAttribute::Previous() -{ - // We are using knowledge of the sentinel. The sentinel - // have a value or name. - if ( prev->value.empty() && prev->name.empty() ) - return 0; - return prev; -} -*/ - -void TiXmlAttribute::Print( FILE* cfile, int /*depth*/, TIXML_STRING* str ) const -{ - TIXML_STRING n, v; - - EncodeString( name, &n ); - EncodeString( value, &v ); - - if (value.find ('\"') == TIXML_STRING::npos) { - if ( cfile ) { - fprintf (cfile, "%s=\"%s\"", n.c_str(), v.c_str() ); - } - if ( str ) { - (*str) += n; (*str) += "=\""; (*str) += v; (*str) += "\""; - } - } - else { - if ( cfile ) { - fprintf (cfile, "%s='%s'", n.c_str(), v.c_str() ); - } - if ( str ) { - (*str) += n; (*str) += "='"; (*str) += v; (*str) += "'"; - } - } -} - - -int TiXmlAttribute::QueryIntValue( int* ival ) const -{ - if ( TIXML_SSCANF( value.c_str(), "%d", ival ) == 1 ) - return TIXML_SUCCESS; - return TIXML_WRONG_TYPE; -} - -int TiXmlAttribute::QueryDoubleValue( double* dval ) const -{ - if ( TIXML_SSCANF( value.c_str(), "%lf", dval ) == 1 ) - return TIXML_SUCCESS; - return TIXML_WRONG_TYPE; -} - -void TiXmlAttribute::SetIntValue( int _value ) -{ - char buf [64]; - #if defined(TIXML_SNPRINTF) - TIXML_SNPRINTF(buf, sizeof(buf), "%d", _value); - #else - sprintf (buf, "%d", _value); - #endif - SetValue (buf); -} - -void TiXmlAttribute::SetDoubleValue( double _value ) -{ - char buf [256]; - #if defined(TIXML_SNPRINTF) - TIXML_SNPRINTF( buf, sizeof(buf), "%g", _value); - #else - sprintf (buf, "%g", _value); - #endif - SetValue (buf); -} - -int TiXmlAttribute::IntValue() const -{ - return atoi (value.c_str ()); -} - -double TiXmlAttribute::DoubleValue() const -{ - return atof (value.c_str ()); -} - - -TiXmlComment::TiXmlComment( const TiXmlComment& copy ) : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) -{ - copy.CopyTo( this ); -} - - -TiXmlComment& TiXmlComment::operator=( const TiXmlComment& base ) -{ - Clear(); - base.CopyTo( this ); - return *this; -} - - -void TiXmlComment::Print( FILE* cfile, int depth ) const -{ - assert( cfile ); - for ( int i=0; i", value.c_str() ); -} - - -void TiXmlComment::CopyTo( TiXmlComment* target ) const -{ - TiXmlNode::CopyTo( target ); -} - - -bool TiXmlComment::Accept( TiXmlVisitor* visitor ) const -{ - return visitor->Visit( *this ); -} - - -TiXmlNode* TiXmlComment::Clone() const -{ - TiXmlComment* clone = new TiXmlComment(); - - if ( !clone ) - return 0; - - CopyTo( clone ); - return clone; -} - - -void TiXmlText::Print( FILE* cfile, int depth ) const -{ - assert( cfile ); - if ( cdata ) - { - int i; - fprintf( cfile, "\n" ); - for ( i=0; i\n", value.c_str() ); // unformatted output - } - else - { - TIXML_STRING buffer; - EncodeString( value, &buffer ); - fprintf( cfile, "%s", buffer.c_str() ); - } -} - - -void TiXmlText::CopyTo( TiXmlText* target ) const -{ - TiXmlNode::CopyTo( target ); - target->cdata = cdata; -} - - -bool TiXmlText::Accept( TiXmlVisitor* visitor ) const -{ - return visitor->Visit( *this ); -} - - -TiXmlNode* TiXmlText::Clone() const -{ - TiXmlText* clone = 0; - clone = new TiXmlText( "" ); - - if ( !clone ) - return 0; - - CopyTo( clone ); - return clone; -} - - -TiXmlDeclaration::TiXmlDeclaration( const char * _version, - const char * _encoding, - const char * _standalone ) - : TiXmlNode( TiXmlNode::TINYXML_DECLARATION ) -{ - version = _version; - encoding = _encoding; - standalone = _standalone; -} - - -#ifdef TIXML_USE_STL -TiXmlDeclaration::TiXmlDeclaration( const std::string& _version, - const std::string& _encoding, - const std::string& _standalone ) - : TiXmlNode( TiXmlNode::TINYXML_DECLARATION ) -{ - version = _version; - encoding = _encoding; - standalone = _standalone; -} -#endif - - -TiXmlDeclaration::TiXmlDeclaration( const TiXmlDeclaration& copy ) - : TiXmlNode( TiXmlNode::TINYXML_DECLARATION ) -{ - copy.CopyTo( this ); -} - - -TiXmlDeclaration& TiXmlDeclaration::operator=( const TiXmlDeclaration& copy ) -{ - Clear(); - copy.CopyTo( this ); - return *this; -} - - -void TiXmlDeclaration::Print( FILE* cfile, int /*depth*/, TIXML_STRING* str ) const -{ - if ( cfile ) fprintf( cfile, "" ); - if ( str ) (*str) += "?>"; -} - - -void TiXmlDeclaration::CopyTo( TiXmlDeclaration* target ) const -{ - TiXmlNode::CopyTo( target ); - - target->version = version; - target->encoding = encoding; - target->standalone = standalone; -} - - -bool TiXmlDeclaration::Accept( TiXmlVisitor* visitor ) const -{ - return visitor->Visit( *this ); -} - - -TiXmlNode* TiXmlDeclaration::Clone() const -{ - TiXmlDeclaration* clone = new TiXmlDeclaration(); - - if ( !clone ) - return 0; - - CopyTo( clone ); - return clone; -} - - -void TiXmlUnknown::Print( FILE* cfile, int depth ) const -{ - for ( int i=0; i", value.c_str() ); -} - - -void TiXmlUnknown::CopyTo( TiXmlUnknown* target ) const -{ - TiXmlNode::CopyTo( target ); -} - - -bool TiXmlUnknown::Accept( TiXmlVisitor* visitor ) const -{ - return visitor->Visit( *this ); -} - - -TiXmlNode* TiXmlUnknown::Clone() const -{ - TiXmlUnknown* clone = new TiXmlUnknown(); - - if ( !clone ) - return 0; - - CopyTo( clone ); - return clone; -} - - -TiXmlAttributeSet::TiXmlAttributeSet() -{ - sentinel.next = &sentinel; - sentinel.prev = &sentinel; -} - - -TiXmlAttributeSet::~TiXmlAttributeSet() -{ - assert( sentinel.next == &sentinel ); - assert( sentinel.prev == &sentinel ); -} - - -void TiXmlAttributeSet::Add( TiXmlAttribute* addMe ) -{ - #ifdef TIXML_USE_STL - assert( !Find( TIXML_STRING( addMe->Name() ) ) ); // Shouldn't be multiply adding to the set. - #else - assert( !Find( addMe->Name() ) ); // Shouldn't be multiply adding to the set. - #endif - - addMe->next = &sentinel; - addMe->prev = sentinel.prev; - - sentinel.prev->next = addMe; - sentinel.prev = addMe; -} - -void TiXmlAttributeSet::Remove( TiXmlAttribute* removeMe ) -{ - TiXmlAttribute* node; - - for( node = sentinel.next; node != &sentinel; node = node->next ) - { - if ( node == removeMe ) - { - node->prev->next = node->next; - node->next->prev = node->prev; - node->next = 0; - node->prev = 0; - return; - } - } - assert( 0 ); // we tried to remove a non-linked attribute. -} - - -#ifdef TIXML_USE_STL -TiXmlAttribute* TiXmlAttributeSet::Find( const std::string& name ) const -{ - for( TiXmlAttribute* node = sentinel.next; node != &sentinel; node = node->next ) - { - if ( node->name == name ) - return node; - } - return 0; -} - -TiXmlAttribute* TiXmlAttributeSet::FindOrCreate( const std::string& _name ) -{ - TiXmlAttribute* attrib = Find( _name ); - if ( !attrib ) { - attrib = new TiXmlAttribute(); - Add( attrib ); - attrib->SetName( _name ); - } - return attrib; -} -#endif - - -TiXmlAttribute* TiXmlAttributeSet::Find( const char* name ) const -{ - for( TiXmlAttribute* node = sentinel.next; node != &sentinel; node = node->next ) - { - if ( strcmp( node->name.c_str(), name ) == 0 ) - return node; - } - return 0; -} - - -TiXmlAttribute* TiXmlAttributeSet::FindOrCreate( const char* _name ) -{ - TiXmlAttribute* attrib = Find( _name ); - if ( !attrib ) { - attrib = new TiXmlAttribute(); - Add( attrib ); - attrib->SetName( _name ); - } - return attrib; -} - - -#ifdef TIXML_USE_STL -std::istream& operator>> (std::istream & in, TiXmlNode & base) -{ - TIXML_STRING tag; - tag.reserve( 8 * 1000 ); - base.StreamIn( &in, &tag ); - - base.Parse( tag.c_str(), 0, TIXML_DEFAULT_ENCODING ); - return in; -} -#endif - - -#ifdef TIXML_USE_STL -std::ostream& operator<< (std::ostream & out, const TiXmlNode & base) -{ - TiXmlPrinter printer; - printer.SetStreamPrinting(); - base.Accept( &printer ); - out << printer.Str(); - - return out; -} - - -std::string& operator<< (std::string& out, const TiXmlNode& base ) -{ - TiXmlPrinter printer; - printer.SetStreamPrinting(); - base.Accept( &printer ); - out.append( printer.Str() ); - - return out; -} -#endif - - -TiXmlHandle TiXmlHandle::FirstChild() const -{ - if ( node ) - { - TiXmlNode* child = node->FirstChild(); - if ( child ) - return TiXmlHandle( child ); - } - return TiXmlHandle( 0 ); -} - - -TiXmlHandle TiXmlHandle::FirstChild( const char * _value ) const -{ - if ( node ) - { - TiXmlNode* child = node->FirstChild( _value ); - if ( child ) - return TiXmlHandle( child ); - } - return TiXmlHandle( 0 ); -} - - -TiXmlHandle TiXmlHandle::FirstChildElement() const -{ - if ( node ) - { - TiXmlElement* child = node->FirstChildElement(); - if ( child ) - return TiXmlHandle( child ); - } - return TiXmlHandle( 0 ); -} - - -TiXmlHandle TiXmlHandle::FirstChildElement( const char * _value ) const -{ - if ( node ) - { - TiXmlElement* child = node->FirstChildElement( _value ); - if ( child ) - return TiXmlHandle( child ); - } - return TiXmlHandle( 0 ); -} - - -TiXmlHandle TiXmlHandle::Child( int count ) const -{ - if ( node ) - { - int i; - TiXmlNode* child = node->FirstChild(); - for ( i=0; - child && iNextSibling(), ++i ) - { - // nothing - } - if ( child ) - return TiXmlHandle( child ); - } - return TiXmlHandle( 0 ); -} - - -TiXmlHandle TiXmlHandle::Child( const char* _value, int count ) const -{ - if ( node ) - { - int i; - TiXmlNode* child = node->FirstChild( _value ); - for ( i=0; - child && iNextSibling( _value ), ++i ) - { - // nothing - } - if ( child ) - return TiXmlHandle( child ); - } - return TiXmlHandle( 0 ); -} - - -TiXmlHandle TiXmlHandle::ChildElement( int count ) const -{ - if ( node ) - { - int i; - TiXmlElement* child = node->FirstChildElement(); - for ( i=0; - child && iNextSiblingElement(), ++i ) - { - // nothing - } - if ( child ) - return TiXmlHandle( child ); - } - return TiXmlHandle( 0 ); -} - - -TiXmlHandle TiXmlHandle::ChildElement( const char* _value, int count ) const -{ - if ( node ) - { - int i; - TiXmlElement* child = node->FirstChildElement( _value ); - for ( i=0; - child && iNextSiblingElement( _value ), ++i ) - { - // nothing - } - if ( child ) - return TiXmlHandle( child ); - } - return TiXmlHandle( 0 ); -} - - -bool TiXmlPrinter::VisitEnter( const TiXmlDocument& ) -{ - return true; -} - -bool TiXmlPrinter::VisitExit( const TiXmlDocument& ) -{ - return true; -} - -bool TiXmlPrinter::VisitEnter( const TiXmlElement& element, const TiXmlAttribute* firstAttribute ) -{ - DoIndent(); - buffer += "<"; - buffer += element.Value(); - - for( const TiXmlAttribute* attrib = firstAttribute; attrib; attrib = attrib->Next() ) - { - buffer += " "; - attrib->Print( 0, 0, &buffer ); - } - - if ( !element.FirstChild() ) - { - buffer += " />"; - DoLineBreak(); - } - else - { - buffer += ">"; - if ( element.FirstChild()->ToText() - && element.LastChild() == element.FirstChild() - && element.FirstChild()->ToText()->CDATA() == false ) - { - simpleTextPrint = true; - // no DoLineBreak()! - } - else - { - DoLineBreak(); - } - } - ++depth; - return true; -} - - -bool TiXmlPrinter::VisitExit( const TiXmlElement& element ) -{ - --depth; - if ( !element.FirstChild() ) - { - // nothing. - } - else - { - if ( simpleTextPrint ) - { - simpleTextPrint = false; - } - else - { - DoIndent(); - } - buffer += ""; - DoLineBreak(); - } - return true; -} - - -bool TiXmlPrinter::Visit( const TiXmlText& text ) -{ - if ( text.CDATA() ) - { - DoIndent(); - buffer += ""; - DoLineBreak(); - } - else if ( simpleTextPrint ) - { - TIXML_STRING str; - TiXmlBase::EncodeString( text.ValueTStr(), &str ); - buffer += str; - } - else - { - DoIndent(); - TIXML_STRING str; - TiXmlBase::EncodeString( text.ValueTStr(), &str ); - buffer += str; - DoLineBreak(); - } - return true; -} - - -bool TiXmlPrinter::Visit( const TiXmlDeclaration& declaration ) -{ - DoIndent(); - declaration.Print( 0, 0, &buffer ); - DoLineBreak(); - return true; -} - - -bool TiXmlPrinter::Visit( const TiXmlComment& comment ) -{ - DoIndent(); - buffer += ""; - DoLineBreak(); - return true; -} - - -bool TiXmlPrinter::Visit( const TiXmlUnknown& unknown ) -{ - DoIndent(); - buffer += "<"; - buffer += unknown.Value(); - buffer += ">"; - DoLineBreak(); - return true; -} - diff --git a/src/win/tinyxml/tinyxml.h b/src/win/tinyxml/tinyxml.h deleted file mode 100644 index a3589e5b2..000000000 --- a/src/win/tinyxml/tinyxml.h +++ /dev/null @@ -1,1805 +0,0 @@ -/* -www.sourceforge.net/projects/tinyxml -Original code by Lee Thomason (www.grinninglizard.com) - -This software is provided 'as-is', without any express or implied -warranty. In no event will the authors be held liable for any -damages arising from the use of this software. - -Permission is granted to anyone to use this software for any -purpose, including commercial applications, and to alter it and -redistribute it freely, subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must -not claim that you wrote the original software. If you use this -software in a product, an acknowledgment in the product documentation -would be appreciated but is not required. - -2. Altered source versions must be plainly marked as such, and -must not be misrepresented as being the original software. - -3. This notice may not be removed or altered from any source -distribution. -*/ - - -#ifndef TINYXML_INCLUDED -#define TINYXML_INCLUDED - -#ifdef _MSC_VER -#pragma warning( push ) -#pragma warning( disable : 4530 ) -#pragma warning( disable : 4786 ) -#endif - -#include -#include -#include -#include -#include - -// Help out windows: -#if defined( _DEBUG ) && !defined( DEBUG ) -#define DEBUG -#endif - -#ifdef TIXML_USE_STL - #include - #include - #include - #define TIXML_STRING std::string -#else - #include "tinystr.h" - #define TIXML_STRING TiXmlString -#endif - -// Deprecated library function hell. Compilers want to use the -// new safe versions. This probably doesn't fully address the problem, -// but it gets closer. There are too many compilers for me to fully -// test. If you get compilation troubles, undefine TIXML_SAFE -#define TIXML_SAFE - -#ifdef TIXML_SAFE - #if defined(_MSC_VER) && (_MSC_VER >= 1400 ) - // Microsoft visual studio, version 2005 and higher. - #define TIXML_SNPRINTF _snprintf_s - #define TIXML_SSCANF sscanf_s - #elif defined(_MSC_VER) && (_MSC_VER >= 1200 ) - // Microsoft visual studio, version 6 and higher. - //#pragma message( "Using _sn* functions." ) - #define TIXML_SNPRINTF _snprintf - #define TIXML_SSCANF sscanf - #elif defined(__GNUC__) && (__GNUC__ >= 3 ) - // GCC version 3 and higher.s - //#warning( "Using sn* functions." ) - #define TIXML_SNPRINTF snprintf - #define TIXML_SSCANF sscanf - #else - #define TIXML_SNPRINTF snprintf - #define TIXML_SSCANF sscanf - #endif -#endif - -class TiXmlDocument; -class TiXmlElement; -class TiXmlComment; -class TiXmlUnknown; -class TiXmlAttribute; -class TiXmlText; -class TiXmlDeclaration; -class TiXmlParsingData; - -const int TIXML_MAJOR_VERSION = 2; -const int TIXML_MINOR_VERSION = 6; -const int TIXML_PATCH_VERSION = 2; - -/* Internal structure for tracking location of items - in the XML file. -*/ -struct TiXmlCursor -{ - TiXmlCursor() { Clear(); } - void Clear() { row = col = -1; } - - int row; // 0 based. - int col; // 0 based. -}; - - -/** - Implements the interface to the "Visitor pattern" (see the Accept() method.) - If you call the Accept() method, it requires being passed a TiXmlVisitor - class to handle callbacks. For nodes that contain other nodes (Document, Element) - you will get called with a VisitEnter/VisitExit pair. Nodes that are always leaves - are simply called with Visit(). - - If you return 'true' from a Visit method, recursive parsing will continue. If you return - false, no children of this node or its sibilings will be Visited. - - All flavors of Visit methods have a default implementation that returns 'true' (continue - visiting). You need to only override methods that are interesting to you. - - Generally Accept() is called on the TiXmlDocument, although all nodes suppert Visiting. - - You should never change the document from a callback. - - @sa TiXmlNode::Accept() -*/ -class TiXmlVisitor -{ -public: - virtual ~TiXmlVisitor() {} - - /// Visit a document. - virtual bool VisitEnter( const TiXmlDocument& /*doc*/ ) { return true; } - /// Visit a document. - virtual bool VisitExit( const TiXmlDocument& /*doc*/ ) { return true; } - - /// Visit an element. - virtual bool VisitEnter( const TiXmlElement& /*element*/, const TiXmlAttribute* /*firstAttribute*/ ) { return true; } - /// Visit an element. - virtual bool VisitExit( const TiXmlElement& /*element*/ ) { return true; } - - /// Visit a declaration - virtual bool Visit( const TiXmlDeclaration& /*declaration*/ ) { return true; } - /// Visit a text node - virtual bool Visit( const TiXmlText& /*text*/ ) { return true; } - /// Visit a comment node - virtual bool Visit( const TiXmlComment& /*comment*/ ) { return true; } - /// Visit an unknown node - virtual bool Visit( const TiXmlUnknown& /*unknown*/ ) { return true; } -}; - -// Only used by Attribute::Query functions -enum -{ - TIXML_SUCCESS, - TIXML_NO_ATTRIBUTE, - TIXML_WRONG_TYPE -}; - - -// Used by the parsing routines. -enum TiXmlEncoding -{ - TIXML_ENCODING_UNKNOWN, - TIXML_ENCODING_UTF8, - TIXML_ENCODING_LEGACY -}; - -const TiXmlEncoding TIXML_DEFAULT_ENCODING = TIXML_ENCODING_UNKNOWN; - -/** TiXmlBase is a base class for every class in TinyXml. - It does little except to establish that TinyXml classes - can be printed and provide some utility functions. - - In XML, the document and elements can contain - other elements and other types of nodes. - - @verbatim - A Document can contain: Element (container or leaf) - Comment (leaf) - Unknown (leaf) - Declaration( leaf ) - - An Element can contain: Element (container or leaf) - Text (leaf) - Attributes (not on tree) - Comment (leaf) - Unknown (leaf) - - A Decleration contains: Attributes (not on tree) - @endverbatim -*/ -class TiXmlBase -{ - friend class TiXmlNode; - friend class TiXmlElement; - friend class TiXmlDocument; - -public: - TiXmlBase() : userData(0) {} - virtual ~TiXmlBase() {} - - /** All TinyXml classes can print themselves to a filestream - or the string class (TiXmlString in non-STL mode, std::string - in STL mode.) Either or both cfile and str can be null. - - This is a formatted print, and will insert - tabs and newlines. - - (For an unformatted stream, use the << operator.) - */ - virtual void Print( FILE* cfile, int depth ) const = 0; - - /** The world does not agree on whether white space should be kept or - not. In order to make everyone happy, these global, static functions - are provided to set whether or not TinyXml will condense all white space - into a single space or not. The default is to condense. Note changing this - value is not thread safe. - */ - static void SetCondenseWhiteSpace( bool condense ) { condenseWhiteSpace = condense; } - - /// Return the current white space setting. - static bool IsWhiteSpaceCondensed() { return condenseWhiteSpace; } - - /** Return the position, in the original source file, of this node or attribute. - The row and column are 1-based. (That is the first row and first column is - 1,1). If the returns values are 0 or less, then the parser does not have - a row and column value. - - Generally, the row and column value will be set when the TiXmlDocument::Load(), - TiXmlDocument::LoadFile(), or any TiXmlNode::Parse() is called. It will NOT be set - when the DOM was created from operator>>. - - The values reflect the initial load. Once the DOM is modified programmatically - (by adding or changing nodes and attributes) the new values will NOT update to - reflect changes in the document. - - There is a minor performance cost to computing the row and column. Computation - can be disabled if TiXmlDocument::SetTabSize() is called with 0 as the value. - - @sa TiXmlDocument::SetTabSize() - */ - int Row() const { return location.row + 1; } - int Column() const { return location.col + 1; } ///< See Row() - - void SetUserData( void* user ) { userData = user; } ///< Set a pointer to arbitrary user data. - void* GetUserData() { return userData; } ///< Get a pointer to arbitrary user data. - const void* GetUserData() const { return userData; } ///< Get a pointer to arbitrary user data. - - // Table that returs, for a given lead byte, the total number of bytes - // in the UTF-8 sequence. - static const int utf8ByteTable[256]; - - virtual const char* Parse( const char* p, - TiXmlParsingData* data, - TiXmlEncoding encoding /*= TIXML_ENCODING_UNKNOWN */ ) = 0; - - /** Expands entities in a string. Note this should not contian the tag's '<', '>', etc, - or they will be transformed into entities! - */ - static void EncodeString( const TIXML_STRING& str, TIXML_STRING* out ); - - enum - { - TIXML_NO_ERROR = 0, - TIXML_ERROR, - TIXML_ERROR_OPENING_FILE, - TIXML_ERROR_PARSING_ELEMENT, - TIXML_ERROR_FAILED_TO_READ_ELEMENT_NAME, - TIXML_ERROR_READING_ELEMENT_VALUE, - TIXML_ERROR_READING_ATTRIBUTES, - TIXML_ERROR_PARSING_EMPTY, - TIXML_ERROR_READING_END_TAG, - TIXML_ERROR_PARSING_UNKNOWN, - TIXML_ERROR_PARSING_COMMENT, - TIXML_ERROR_PARSING_DECLARATION, - TIXML_ERROR_DOCUMENT_EMPTY, - TIXML_ERROR_EMBEDDED_NULL, - TIXML_ERROR_PARSING_CDATA, - TIXML_ERROR_DOCUMENT_TOP_ONLY, - - TIXML_ERROR_STRING_COUNT - }; - -protected: - - static const char* SkipWhiteSpace( const char*, TiXmlEncoding encoding ); - - inline static bool IsWhiteSpace( char c ) - { - return ( isspace( (unsigned char) c ) || c == '\n' || c == '\r' ); - } - inline static bool IsWhiteSpace( int c ) - { - if ( c < 256 ) - return IsWhiteSpace( (char) c ); - return false; // Again, only truly correct for English/Latin...but usually works. - } - - #ifdef TIXML_USE_STL - static bool StreamWhiteSpace( std::istream * in, TIXML_STRING * tag ); - static bool StreamTo( std::istream * in, int character, TIXML_STRING * tag ); - #endif - - /* Reads an XML name into the string provided. Returns - a pointer just past the last character of the name, - or 0 if the function has an error. - */ - static const char* ReadName( const char* p, TIXML_STRING* name, TiXmlEncoding encoding ); - - /* Reads text. Returns a pointer past the given end tag. - Wickedly complex options, but it keeps the (sensitive) code in one place. - */ - static const char* ReadText( const char* in, // where to start - TIXML_STRING* text, // the string read - bool ignoreWhiteSpace, // whether to keep the white space - const char* endTag, // what ends this text - bool ignoreCase, // whether to ignore case in the end tag - TiXmlEncoding encoding ); // the current encoding - - // If an entity has been found, transform it into a character. - static const char* GetEntity( const char* in, char* value, int* length, TiXmlEncoding encoding ); - - // Get a character, while interpreting entities. - // The length can be from 0 to 4 bytes. - inline static const char* GetChar( const char* p, char* _value, int* length, TiXmlEncoding encoding ) - { - assert( p ); - if ( encoding == TIXML_ENCODING_UTF8 ) - { - *length = utf8ByteTable[ *((const unsigned char*)p) ]; - assert( *length >= 0 && *length < 5 ); - } - else - { - *length = 1; - } - - if ( *length == 1 ) - { - if ( *p == '&' ) - return GetEntity( p, _value, length, encoding ); - *_value = *p; - return p+1; - } - else if ( *length ) - { - //strncpy( _value, p, *length ); // lots of compilers don't like this function (unsafe), - // and the null terminator isn't needed - for( int i=0; p[i] && i<*length; ++i ) { - _value[i] = p[i]; - } - return p + (*length); - } - else - { - // Not valid text. - return 0; - } - } - - // Return true if the next characters in the stream are any of the endTag sequences. - // Ignore case only works for english, and should only be relied on when comparing - // to English words: StringEqual( p, "version", true ) is fine. - static bool StringEqual( const char* p, - const char* endTag, - bool ignoreCase, - TiXmlEncoding encoding ); - - static const char* errorString[ TIXML_ERROR_STRING_COUNT ]; - - TiXmlCursor location; - - /// Field containing a generic user pointer - void* userData; - - // None of these methods are reliable for any language except English. - // Good for approximation, not great for accuracy. - static int IsAlpha( unsigned char anyByte, TiXmlEncoding encoding ); - static int IsAlphaNum( unsigned char anyByte, TiXmlEncoding encoding ); - inline static int ToLower( int v, TiXmlEncoding encoding ) - { - if ( encoding == TIXML_ENCODING_UTF8 ) - { - if ( v < 128 ) return tolower( v ); - return v; - } - else - { - return tolower( v ); - } - } - static void ConvertUTF32ToUTF8( unsigned long input, char* output, int* length ); - -private: - TiXmlBase( const TiXmlBase& ); // not implemented. - void operator=( const TiXmlBase& base ); // not allowed. - - struct Entity - { - const char* str; - unsigned int strLength; - char chr; - }; - enum - { - NUM_ENTITY = 5, - MAX_ENTITY_LENGTH = 6 - - }; - static Entity entity[ NUM_ENTITY ]; - static bool condenseWhiteSpace; -}; - - -/** The parent class for everything in the Document Object Model. - (Except for attributes). - Nodes have siblings, a parent, and children. A node can be - in a document, or stand on its own. The type of a TiXmlNode - can be queried, and it can be cast to its more defined type. -*/ -class TiXmlNode : public TiXmlBase -{ - friend class TiXmlDocument; - friend class TiXmlElement; - -public: - #ifdef TIXML_USE_STL - - /** An input stream operator, for every class. Tolerant of newlines and - formatting, but doesn't expect them. - */ - friend std::istream& operator >> (std::istream& in, TiXmlNode& base); - - /** An output stream operator, for every class. Note that this outputs - without any newlines or formatting, as opposed to Print(), which - includes tabs and new lines. - - The operator<< and operator>> are not completely symmetric. Writing - a node to a stream is very well defined. You'll get a nice stream - of output, without any extra whitespace or newlines. - - But reading is not as well defined. (As it always is.) If you create - a TiXmlElement (for example) and read that from an input stream, - the text needs to define an element or junk will result. This is - true of all input streams, but it's worth keeping in mind. - - A TiXmlDocument will read nodes until it reads a root element, and - all the children of that root element. - */ - friend std::ostream& operator<< (std::ostream& out, const TiXmlNode& base); - - /// Appends the XML node or attribute to a std::string. - friend std::string& operator<< (std::string& out, const TiXmlNode& base ); - - #endif - - /** The types of XML nodes supported by TinyXml. (All the - unsupported types are picked up by UNKNOWN.) - */ - enum NodeType - { - TINYXML_DOCUMENT, - TINYXML_ELEMENT, - TINYXML_COMMENT, - TINYXML_UNKNOWN, - TINYXML_TEXT, - TINYXML_DECLARATION, - TINYXML_TYPECOUNT - }; - - virtual ~TiXmlNode(); - - /** The meaning of 'value' changes for the specific type of - TiXmlNode. - @verbatim - Document: filename of the xml file - Element: name of the element - Comment: the comment text - Unknown: the tag contents - Text: the text string - @endverbatim - - The subclasses will wrap this function. - */ - const char *Value() const { return value.c_str (); } - - #ifdef TIXML_USE_STL - /** Return Value() as a std::string. If you only use STL, - this is more efficient than calling Value(). - Only available in STL mode. - */ - const std::string& ValueStr() const { return value; } - #endif - - const TIXML_STRING& ValueTStr() const { return value; } - - /** Changes the value of the node. Defined as: - @verbatim - Document: filename of the xml file - Element: name of the element - Comment: the comment text - Unknown: the tag contents - Text: the text string - @endverbatim - */ - void SetValue(const char * _value) { value = _value;} - - #ifdef TIXML_USE_STL - /// STL std::string form. - void SetValue( const std::string& _value ) { value = _value; } - #endif - - /// Delete all the children of this node. Does not affect 'this'. - void Clear(); - - /// One step up the DOM. - TiXmlNode* Parent() { return parent; } - const TiXmlNode* Parent() const { return parent; } - - const TiXmlNode* FirstChild() const { return firstChild; } ///< The first child of this node. Will be null if there are no children. - TiXmlNode* FirstChild() { return firstChild; } - const TiXmlNode* FirstChild( const char * value ) const; ///< The first child of this node with the matching 'value'. Will be null if none found. - /// The first child of this node with the matching 'value'. Will be null if none found. - TiXmlNode* FirstChild( const char * _value ) { - // Call through to the const version - safe since nothing is changed. Exiting syntax: cast this to a const (always safe) - // call the method, cast the return back to non-const. - return const_cast< TiXmlNode* > ((const_cast< const TiXmlNode* >(this))->FirstChild( _value )); - } - const TiXmlNode* LastChild() const { return lastChild; } /// The last child of this node. Will be null if there are no children. - TiXmlNode* LastChild() { return lastChild; } - - const TiXmlNode* LastChild( const char * value ) const; /// The last child of this node matching 'value'. Will be null if there are no children. - TiXmlNode* LastChild( const char * _value ) { - return const_cast< TiXmlNode* > ((const_cast< const TiXmlNode* >(this))->LastChild( _value )); - } - - #ifdef TIXML_USE_STL - const TiXmlNode* FirstChild( const std::string& _value ) const { return FirstChild (_value.c_str ()); } ///< STL std::string form. - TiXmlNode* FirstChild( const std::string& _value ) { return FirstChild (_value.c_str ()); } ///< STL std::string form. - const TiXmlNode* LastChild( const std::string& _value ) const { return LastChild (_value.c_str ()); } ///< STL std::string form. - TiXmlNode* LastChild( const std::string& _value ) { return LastChild (_value.c_str ()); } ///< STL std::string form. - #endif - - /** An alternate way to walk the children of a node. - One way to iterate over nodes is: - @verbatim - for( child = parent->FirstChild(); child; child = child->NextSibling() ) - @endverbatim - - IterateChildren does the same thing with the syntax: - @verbatim - child = 0; - while( child = parent->IterateChildren( child ) ) - @endverbatim - - IterateChildren takes the previous child as input and finds - the next one. If the previous child is null, it returns the - first. IterateChildren will return null when done. - */ - const TiXmlNode* IterateChildren( const TiXmlNode* previous ) const; - TiXmlNode* IterateChildren( const TiXmlNode* previous ) { - return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->IterateChildren( previous ) ); - } - - /// This flavor of IterateChildren searches for children with a particular 'value' - const TiXmlNode* IterateChildren( const char * value, const TiXmlNode* previous ) const; - TiXmlNode* IterateChildren( const char * _value, const TiXmlNode* previous ) { - return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->IterateChildren( _value, previous ) ); - } - - #ifdef TIXML_USE_STL - const TiXmlNode* IterateChildren( const std::string& _value, const TiXmlNode* previous ) const { return IterateChildren (_value.c_str (), previous); } ///< STL std::string form. - TiXmlNode* IterateChildren( const std::string& _value, const TiXmlNode* previous ) { return IterateChildren (_value.c_str (), previous); } ///< STL std::string form. - #endif - - /** Add a new node related to this. Adds a child past the LastChild. - Returns a pointer to the new object or NULL if an error occured. - */ - TiXmlNode* InsertEndChild( const TiXmlNode& addThis ); - - - /** Add a new node related to this. Adds a child past the LastChild. - - NOTE: the node to be added is passed by pointer, and will be - henceforth owned (and deleted) by tinyXml. This method is efficient - and avoids an extra copy, but should be used with care as it - uses a different memory model than the other insert functions. - - @sa InsertEndChild - */ - TiXmlNode* LinkEndChild( TiXmlNode* addThis ); - - /** Add a new node related to this. Adds a child before the specified child. - Returns a pointer to the new object or NULL if an error occured. - */ - TiXmlNode* InsertBeforeChild( TiXmlNode* beforeThis, const TiXmlNode& addThis ); - - /** Add a new node related to this. Adds a child after the specified child. - Returns a pointer to the new object or NULL if an error occured. - */ - TiXmlNode* InsertAfterChild( TiXmlNode* afterThis, const TiXmlNode& addThis ); - - /** Replace a child of this node. - Returns a pointer to the new object or NULL if an error occured. - */ - TiXmlNode* ReplaceChild( TiXmlNode* replaceThis, const TiXmlNode& withThis ); - - /// Delete a child of this node. - bool RemoveChild( TiXmlNode* removeThis ); - - /// Navigate to a sibling node. - const TiXmlNode* PreviousSibling() const { return prev; } - TiXmlNode* PreviousSibling() { return prev; } - - /// Navigate to a sibling node. - const TiXmlNode* PreviousSibling( const char * ) const; - TiXmlNode* PreviousSibling( const char *_prev ) { - return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->PreviousSibling( _prev ) ); - } - - #ifdef TIXML_USE_STL - const TiXmlNode* PreviousSibling( const std::string& _value ) const { return PreviousSibling (_value.c_str ()); } ///< STL std::string form. - TiXmlNode* PreviousSibling( const std::string& _value ) { return PreviousSibling (_value.c_str ()); } ///< STL std::string form. - const TiXmlNode* NextSibling( const std::string& _value) const { return NextSibling (_value.c_str ()); } ///< STL std::string form. - TiXmlNode* NextSibling( const std::string& _value) { return NextSibling (_value.c_str ()); } ///< STL std::string form. - #endif - - /// Navigate to a sibling node. - const TiXmlNode* NextSibling() const { return next; } - TiXmlNode* NextSibling() { return next; } - - /// Navigate to a sibling node with the given 'value'. - const TiXmlNode* NextSibling( const char * ) const; - TiXmlNode* NextSibling( const char* _next ) { - return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->NextSibling( _next ) ); - } - - /** Convenience function to get through elements. - Calls NextSibling and ToElement. Will skip all non-Element - nodes. Returns 0 if there is not another element. - */ - const TiXmlElement* NextSiblingElement() const; - TiXmlElement* NextSiblingElement() { - return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->NextSiblingElement() ); - } - - /** Convenience function to get through elements. - Calls NextSibling and ToElement. Will skip all non-Element - nodes. Returns 0 if there is not another element. - */ - const TiXmlElement* NextSiblingElement( const char * ) const; - TiXmlElement* NextSiblingElement( const char *_next ) { - return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->NextSiblingElement( _next ) ); - } - - #ifdef TIXML_USE_STL - const TiXmlElement* NextSiblingElement( const std::string& _value) const { return NextSiblingElement (_value.c_str ()); } ///< STL std::string form. - TiXmlElement* NextSiblingElement( const std::string& _value) { return NextSiblingElement (_value.c_str ()); } ///< STL std::string form. - #endif - - /// Convenience function to get through elements. - const TiXmlElement* FirstChildElement() const; - TiXmlElement* FirstChildElement() { - return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->FirstChildElement() ); - } - - /// Convenience function to get through elements. - const TiXmlElement* FirstChildElement( const char * _value ) const; - TiXmlElement* FirstChildElement( const char * _value ) { - return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->FirstChildElement( _value ) ); - } - - #ifdef TIXML_USE_STL - const TiXmlElement* FirstChildElement( const std::string& _value ) const { return FirstChildElement (_value.c_str ()); } ///< STL std::string form. - TiXmlElement* FirstChildElement( const std::string& _value ) { return FirstChildElement (_value.c_str ()); } ///< STL std::string form. - #endif - - /** Query the type (as an enumerated value, above) of this node. - The possible types are: TINYXML_DOCUMENT, TINYXML_ELEMENT, TINYXML_COMMENT, - TINYXML_UNKNOWN, TINYXML_TEXT, and TINYXML_DECLARATION. - */ - int Type() const { return type; } - - /** Return a pointer to the Document this node lives in. - Returns null if not in a document. - */ - const TiXmlDocument* GetDocument() const; - TiXmlDocument* GetDocument() { - return const_cast< TiXmlDocument* >( (const_cast< const TiXmlNode* >(this))->GetDocument() ); - } - - /// Returns true if this node has no children. - bool NoChildren() const { return !firstChild; } - - virtual const TiXmlDocument* ToDocument() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlElement* ToElement() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlComment* ToComment() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlUnknown* ToUnknown() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlText* ToText() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlDeclaration* ToDeclaration() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - - virtual TiXmlDocument* ToDocument() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlElement* ToElement() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlComment* ToComment() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlUnknown* ToUnknown() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlText* ToText() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlDeclaration* ToDeclaration() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - - /** Create an exact duplicate of this node and return it. The memory must be deleted - by the caller. - */ - virtual TiXmlNode* Clone() const = 0; - - /** Accept a hierchical visit the nodes in the TinyXML DOM. Every node in the - XML tree will be conditionally visited and the host will be called back - via the TiXmlVisitor interface. - - This is essentially a SAX interface for TinyXML. (Note however it doesn't re-parse - the XML for the callbacks, so the performance of TinyXML is unchanged by using this - interface versus any other.) - - The interface has been based on ideas from: - - - http://www.saxproject.org/ - - http://c2.com/cgi/wiki?HierarchicalVisitorPattern - - Which are both good references for "visiting". - - An example of using Accept(): - @verbatim - TiXmlPrinter printer; - tinyxmlDoc.Accept( &printer ); - const char* xmlcstr = printer.CStr(); - @endverbatim - */ - virtual bool Accept( TiXmlVisitor* visitor ) const = 0; - -protected: - TiXmlNode( NodeType _type ); - - // Copy to the allocated object. Shared functionality between Clone, Copy constructor, - // and the assignment operator. - void CopyTo( TiXmlNode* target ) const; - - #ifdef TIXML_USE_STL - // The real work of the input operator. - virtual void StreamIn( std::istream* in, TIXML_STRING* tag ) = 0; - #endif - - // Figure out what is at *p, and parse it. Returns null if it is not an xml node. - TiXmlNode* Identify( const char* start, TiXmlEncoding encoding ); - - TiXmlNode* parent; - NodeType type; - - TiXmlNode* firstChild; - TiXmlNode* lastChild; - - TIXML_STRING value; - - TiXmlNode* prev; - TiXmlNode* next; - -private: - TiXmlNode( const TiXmlNode& ); // not implemented. - void operator=( const TiXmlNode& base ); // not allowed. -}; - - -/** An attribute is a name-value pair. Elements have an arbitrary - number of attributes, each with a unique name. - - @note The attributes are not TiXmlNodes, since they are not - part of the tinyXML document object model. There are other - suggested ways to look at this problem. -*/ -class TiXmlAttribute : public TiXmlBase -{ - friend class TiXmlAttributeSet; - -public: - /// Construct an empty attribute. - TiXmlAttribute() : TiXmlBase() - { - document = 0; - prev = next = 0; - } - - #ifdef TIXML_USE_STL - /// std::string constructor. - TiXmlAttribute( const std::string& _name, const std::string& _value ) - { - name = _name; - value = _value; - document = 0; - prev = next = 0; - } - #endif - - /// Construct an attribute with a name and value. - TiXmlAttribute( const char * _name, const char * _value ) - { - name = _name; - value = _value; - document = 0; - prev = next = 0; - } - - const char* Name() const { return name.c_str(); } ///< Return the name of this attribute. - const char* Value() const { return value.c_str(); } ///< Return the value of this attribute. - #ifdef TIXML_USE_STL - const std::string& ValueStr() const { return value; } ///< Return the value of this attribute. - #endif - int IntValue() const; ///< Return the value of this attribute, converted to an integer. - double DoubleValue() const; ///< Return the value of this attribute, converted to a double. - - // Get the tinyxml string representation - const TIXML_STRING& NameTStr() const { return name; } - - /** QueryIntValue examines the value string. It is an alternative to the - IntValue() method with richer error checking. - If the value is an integer, it is stored in 'value' and - the call returns TIXML_SUCCESS. If it is not - an integer, it returns TIXML_WRONG_TYPE. - - A specialized but useful call. Note that for success it returns 0, - which is the opposite of almost all other TinyXml calls. - */ - int QueryIntValue( int* _value ) const; - /// QueryDoubleValue examines the value string. See QueryIntValue(). - int QueryDoubleValue( double* _value ) const; - - void SetName( const char* _name ) { name = _name; } ///< Set the name of this attribute. - void SetValue( const char* _value ) { value = _value; } ///< Set the value. - - void SetIntValue( int _value ); ///< Set the value from an integer. - void SetDoubleValue( double _value ); ///< Set the value from a double. - - #ifdef TIXML_USE_STL - /// STL std::string form. - void SetName( const std::string& _name ) { name = _name; } - /// STL std::string form. - void SetValue( const std::string& _value ) { value = _value; } - #endif - - /// Get the next sibling attribute in the DOM. Returns null at end. - const TiXmlAttribute* Next() const; - TiXmlAttribute* Next() { - return const_cast< TiXmlAttribute* >( (const_cast< const TiXmlAttribute* >(this))->Next() ); - } - - /// Get the previous sibling attribute in the DOM. Returns null at beginning. - const TiXmlAttribute* Previous() const; - TiXmlAttribute* Previous() { - return const_cast< TiXmlAttribute* >( (const_cast< const TiXmlAttribute* >(this))->Previous() ); - } - - bool operator==( const TiXmlAttribute& rhs ) const { return rhs.name == name; } - bool operator<( const TiXmlAttribute& rhs ) const { return name < rhs.name; } - bool operator>( const TiXmlAttribute& rhs ) const { return name > rhs.name; } - - /* Attribute parsing starts: first letter of the name - returns: the next char after the value end quote - */ - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - // Prints this Attribute to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const { - Print( cfile, depth, 0 ); - } - void Print( FILE* cfile, int depth, TIXML_STRING* str ) const; - - // [internal use] - // Set the document pointer so the attribute can report errors. - void SetDocument( TiXmlDocument* doc ) { document = doc; } - -private: - TiXmlAttribute( const TiXmlAttribute& ); // not implemented. - void operator=( const TiXmlAttribute& base ); // not allowed. - - TiXmlDocument* document; // A pointer back to a document, for error reporting. - TIXML_STRING name; - TIXML_STRING value; - TiXmlAttribute* prev; - TiXmlAttribute* next; -}; - - -/* A class used to manage a group of attributes. - It is only used internally, both by the ELEMENT and the DECLARATION. - - The set can be changed transparent to the Element and Declaration - classes that use it, but NOT transparent to the Attribute - which has to implement a next() and previous() method. Which makes - it a bit problematic and prevents the use of STL. - - This version is implemented with circular lists because: - - I like circular lists - - it demonstrates some independence from the (typical) doubly linked list. -*/ -class TiXmlAttributeSet -{ -public: - TiXmlAttributeSet(); - ~TiXmlAttributeSet(); - - void Add( TiXmlAttribute* attribute ); - void Remove( TiXmlAttribute* attribute ); - - const TiXmlAttribute* First() const { return ( sentinel.next == &sentinel ) ? 0 : sentinel.next; } - TiXmlAttribute* First() { return ( sentinel.next == &sentinel ) ? 0 : sentinel.next; } - const TiXmlAttribute* Last() const { return ( sentinel.prev == &sentinel ) ? 0 : sentinel.prev; } - TiXmlAttribute* Last() { return ( sentinel.prev == &sentinel ) ? 0 : sentinel.prev; } - - TiXmlAttribute* Find( const char* _name ) const; - TiXmlAttribute* FindOrCreate( const char* _name ); - -# ifdef TIXML_USE_STL - TiXmlAttribute* Find( const std::string& _name ) const; - TiXmlAttribute* FindOrCreate( const std::string& _name ); -# endif - - -private: - //*ME: Because of hidden/disabled copy-construktor in TiXmlAttribute (sentinel-element), - //*ME: this class must be also use a hidden/disabled copy-constructor !!! - TiXmlAttributeSet( const TiXmlAttributeSet& ); // not allowed - void operator=( const TiXmlAttributeSet& ); // not allowed (as TiXmlAttribute) - - TiXmlAttribute sentinel; -}; - - -/** The element is a container class. It has a value, the element name, - and can contain other elements, text, comments, and unknowns. - Elements also contain an arbitrary number of attributes. -*/ -class TiXmlElement : public TiXmlNode -{ -public: - /// Construct an element. - TiXmlElement (const char * in_value); - - #ifdef TIXML_USE_STL - /// std::string constructor. - TiXmlElement( const std::string& _value ); - #endif - - TiXmlElement( const TiXmlElement& ); - - TiXmlElement& operator=( const TiXmlElement& base ); - - virtual ~TiXmlElement(); - - /** Given an attribute name, Attribute() returns the value - for the attribute of that name, or null if none exists. - */ - const char* Attribute( const char* name ) const; - - /** Given an attribute name, Attribute() returns the value - for the attribute of that name, or null if none exists. - If the attribute exists and can be converted to an integer, - the integer value will be put in the return 'i', if 'i' - is non-null. - */ - const char* Attribute( const char* name, int* i ) const; - - /** Given an attribute name, Attribute() returns the value - for the attribute of that name, or null if none exists. - If the attribute exists and can be converted to an double, - the double value will be put in the return 'd', if 'd' - is non-null. - */ - const char* Attribute( const char* name, double* d ) const; - - /** QueryIntAttribute examines the attribute - it is an alternative to the - Attribute() method with richer error checking. - If the attribute is an integer, it is stored in 'value' and - the call returns TIXML_SUCCESS. If it is not - an integer, it returns TIXML_WRONG_TYPE. If the attribute - does not exist, then TIXML_NO_ATTRIBUTE is returned. - */ - int QueryIntAttribute( const char* name, int* _value ) const; - /// QueryUnsignedAttribute examines the attribute - see QueryIntAttribute(). - int QueryUnsignedAttribute( const char* name, unsigned* _value ) const; - /** QueryBoolAttribute examines the attribute - see QueryIntAttribute(). - Note that '1', 'true', or 'yes' are considered true, while '0', 'false' - and 'no' are considered false. - */ - int QueryBoolAttribute( const char* name, bool* _value ) const; - /// QueryDoubleAttribute examines the attribute - see QueryIntAttribute(). - int QueryDoubleAttribute( const char* name, double* _value ) const; - /// QueryFloatAttribute examines the attribute - see QueryIntAttribute(). - int QueryFloatAttribute( const char* name, float* _value ) const { - double d; - int result = QueryDoubleAttribute( name, &d ); - if ( result == TIXML_SUCCESS ) { - *_value = (float)d; - } - return result; - } - - #ifdef TIXML_USE_STL - /// QueryStringAttribute examines the attribute - see QueryIntAttribute(). - int QueryStringAttribute( const char* name, std::string* _value ) const { - const char* cstr = Attribute( name ); - if ( cstr ) { - *_value = std::string( cstr ); - return TIXML_SUCCESS; - } - return TIXML_NO_ATTRIBUTE; - } - - /** Template form of the attribute query which will try to read the - attribute into the specified type. Very easy, very powerful, but - be careful to make sure to call this with the correct type. - - NOTE: This method doesn't work correctly for 'string' types that contain spaces. - - @return TIXML_SUCCESS, TIXML_WRONG_TYPE, or TIXML_NO_ATTRIBUTE - */ - template< typename T > int QueryValueAttribute( const std::string& name, T* outValue ) const - { - const TiXmlAttribute* node = attributeSet.Find( name ); - if ( !node ) - return TIXML_NO_ATTRIBUTE; - - std::stringstream sstream( node->ValueStr() ); - sstream >> *outValue; - if ( !sstream.fail() ) - return TIXML_SUCCESS; - return TIXML_WRONG_TYPE; - } - - int QueryValueAttribute( const std::string& name, std::string* outValue ) const - { - const TiXmlAttribute* node = attributeSet.Find( name ); - if ( !node ) - return TIXML_NO_ATTRIBUTE; - *outValue = node->ValueStr(); - return TIXML_SUCCESS; - } - #endif - - /** Sets an attribute of name to a given value. The attribute - will be created if it does not exist, or changed if it does. - */ - void SetAttribute( const char* name, const char * _value ); - - #ifdef TIXML_USE_STL - const std::string* Attribute( const std::string& name ) const; - const std::string* Attribute( const std::string& name, int* i ) const; - const std::string* Attribute( const std::string& name, double* d ) const; - int QueryIntAttribute( const std::string& name, int* _value ) const; - int QueryDoubleAttribute( const std::string& name, double* _value ) const; - - /// STL std::string form. - void SetAttribute( const std::string& name, const std::string& _value ); - ///< STL std::string form. - void SetAttribute( const std::string& name, int _value ); - ///< STL std::string form. - void SetDoubleAttribute( const std::string& name, double value ); - #endif - - /** Sets an attribute of name to a given value. The attribute - will be created if it does not exist, or changed if it does. - */ - void SetAttribute( const char * name, int value ); - - /** Sets an attribute of name to a given value. The attribute - will be created if it does not exist, or changed if it does. - */ - void SetDoubleAttribute( const char * name, double value ); - - /** Deletes an attribute with the given name. - */ - void RemoveAttribute( const char * name ); - #ifdef TIXML_USE_STL - void RemoveAttribute( const std::string& name ) { RemoveAttribute (name.c_str ()); } ///< STL std::string form. - #endif - - const TiXmlAttribute* FirstAttribute() const { return attributeSet.First(); } ///< Access the first attribute in this element. - TiXmlAttribute* FirstAttribute() { return attributeSet.First(); } - const TiXmlAttribute* LastAttribute() const { return attributeSet.Last(); } ///< Access the last attribute in this element. - TiXmlAttribute* LastAttribute() { return attributeSet.Last(); } - - /** Convenience function for easy access to the text inside an element. Although easy - and concise, GetText() is limited compared to getting the TiXmlText child - and accessing it directly. - - If the first child of 'this' is a TiXmlText, the GetText() - returns the character string of the Text node, else null is returned. - - This is a convenient method for getting the text of simple contained text: - @verbatim - This is text - const char* str = fooElement->GetText(); - @endverbatim - - 'str' will be a pointer to "This is text". - - Note that this function can be misleading. If the element foo was created from - this XML: - @verbatim - This is text - @endverbatim - - then the value of str would be null. The first child node isn't a text node, it is - another element. From this XML: - @verbatim - This is text - @endverbatim - GetText() will return "This is ". - - WARNING: GetText() accesses a child node - don't become confused with the - similarly named TiXmlHandle::Text() and TiXmlNode::ToText() which are - safe type casts on the referenced node. - */ - const char* GetText() const; - - /// Creates a new Element and returns it - the returned element is a copy. - virtual TiXmlNode* Clone() const; - // Print the Element to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const; - - /* Attribtue parsing starts: next char past '<' - returns: next char past '>' - */ - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlElement* ToElement() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlElement* ToElement() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* visitor ) const; - -protected: - - void CopyTo( TiXmlElement* target ) const; - void ClearThis(); // like clear, but initializes 'this' object as well - - // Used to be public [internal use] - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - /* [internal use] - Reads the "value" of the element -- another element, or text. - This should terminate with the current end tag. - */ - const char* ReadValue( const char* in, TiXmlParsingData* prevData, TiXmlEncoding encoding ); - -private: - TiXmlAttributeSet attributeSet; -}; - - -/** An XML comment. -*/ -class TiXmlComment : public TiXmlNode -{ -public: - /// Constructs an empty comment. - TiXmlComment() : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) {} - /// Construct a comment from text. - TiXmlComment( const char* _value ) : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) { - SetValue( _value ); - } - TiXmlComment( const TiXmlComment& ); - TiXmlComment& operator=( const TiXmlComment& base ); - - virtual ~TiXmlComment() {} - - /// Returns a copy of this Comment. - virtual TiXmlNode* Clone() const; - // Write this Comment to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const; - - /* Attribtue parsing starts: at the ! of the !-- - returns: next char past '>' - */ - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlComment* ToComment() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlComment* ToComment() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* visitor ) const; - -protected: - void CopyTo( TiXmlComment* target ) const; - - // used to be public - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif -// virtual void StreamOut( TIXML_OSTREAM * out ) const; - -private: - -}; - - -/** XML text. A text node can have 2 ways to output the next. "normal" output - and CDATA. It will default to the mode it was parsed from the XML file and - you generally want to leave it alone, but you can change the output mode with - SetCDATA() and query it with CDATA(). -*/ -class TiXmlText : public TiXmlNode -{ - friend class TiXmlElement; -public: - /** Constructor for text element. By default, it is treated as - normal, encoded text. If you want it be output as a CDATA text - element, set the parameter _cdata to 'true' - */ - TiXmlText (const char * initValue ) : TiXmlNode (TiXmlNode::TINYXML_TEXT) - { - SetValue( initValue ); - cdata = false; - } - virtual ~TiXmlText() {} - - #ifdef TIXML_USE_STL - /// Constructor. - TiXmlText( const std::string& initValue ) : TiXmlNode (TiXmlNode::TINYXML_TEXT) - { - SetValue( initValue ); - cdata = false; - } - #endif - - TiXmlText( const TiXmlText& copy ) : TiXmlNode( TiXmlNode::TINYXML_TEXT ) { copy.CopyTo( this ); } - TiXmlText& operator=( const TiXmlText& base ) { base.CopyTo( this ); return *this; } - - // Write this text object to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const; - - /// Queries whether this represents text using a CDATA section. - bool CDATA() const { return cdata; } - /// Turns on or off a CDATA representation of text. - void SetCDATA( bool _cdata ) { cdata = _cdata; } - - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlText* ToText() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlText* ToText() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* content ) const; - -protected : - /// [internal use] Creates a new Element and returns it. - virtual TiXmlNode* Clone() const; - void CopyTo( TiXmlText* target ) const; - - bool Blank() const; // returns true if all white space and new lines - // [internal use] - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - -private: - bool cdata; // true if this should be input and output as a CDATA style text element -}; - - -/** In correct XML the declaration is the first entry in the file. - @verbatim - - @endverbatim - - TinyXml will happily read or write files without a declaration, - however. There are 3 possible attributes to the declaration: - version, encoding, and standalone. - - Note: In this version of the code, the attributes are - handled as special cases, not generic attributes, simply - because there can only be at most 3 and they are always the same. -*/ -class TiXmlDeclaration : public TiXmlNode -{ -public: - /// Construct an empty declaration. - TiXmlDeclaration() : TiXmlNode( TiXmlNode::TINYXML_DECLARATION ) {} - -#ifdef TIXML_USE_STL - /// Constructor. - TiXmlDeclaration( const std::string& _version, - const std::string& _encoding, - const std::string& _standalone ); -#endif - - /// Construct. - TiXmlDeclaration( const char* _version, - const char* _encoding, - const char* _standalone ); - - TiXmlDeclaration( const TiXmlDeclaration& copy ); - TiXmlDeclaration& operator=( const TiXmlDeclaration& copy ); - - virtual ~TiXmlDeclaration() {} - - /// Version. Will return an empty string if none was found. - const char *Version() const { return version.c_str (); } - /// Encoding. Will return an empty string if none was found. - const char *Encoding() const { return encoding.c_str (); } - /// Is this a standalone document? - const char *Standalone() const { return standalone.c_str (); } - - /// Creates a copy of this Declaration and returns it. - virtual TiXmlNode* Clone() const; - // Print this declaration to a FILE stream. - virtual void Print( FILE* cfile, int depth, TIXML_STRING* str ) const; - virtual void Print( FILE* cfile, int depth ) const { - Print( cfile, depth, 0 ); - } - - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlDeclaration* ToDeclaration() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlDeclaration* ToDeclaration() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* visitor ) const; - -protected: - void CopyTo( TiXmlDeclaration* target ) const; - // used to be public - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - -private: - - TIXML_STRING version; - TIXML_STRING encoding; - TIXML_STRING standalone; -}; - - -/** Any tag that tinyXml doesn't recognize is saved as an - unknown. It is a tag of text, but should not be modified. - It will be written back to the XML, unchanged, when the file - is saved. - - DTD tags get thrown into TiXmlUnknowns. -*/ -class TiXmlUnknown : public TiXmlNode -{ -public: - TiXmlUnknown() : TiXmlNode( TiXmlNode::TINYXML_UNKNOWN ) {} - virtual ~TiXmlUnknown() {} - - TiXmlUnknown( const TiXmlUnknown& copy ) : TiXmlNode( TiXmlNode::TINYXML_UNKNOWN ) { copy.CopyTo( this ); } - TiXmlUnknown& operator=( const TiXmlUnknown& copy ) { copy.CopyTo( this ); return *this; } - - /// Creates a copy of this Unknown and returns it. - virtual TiXmlNode* Clone() const; - // Print this Unknown to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const; - - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlUnknown* ToUnknown() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlUnknown* ToUnknown() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* content ) const; - -protected: - void CopyTo( TiXmlUnknown* target ) const; - - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - -private: - -}; - - -/** Always the top level node. A document binds together all the - XML pieces. It can be saved, loaded, and printed to the screen. - The 'value' of a document node is the xml file name. -*/ -class TiXmlDocument : public TiXmlNode -{ -public: - /// Create an empty document, that has no name. - TiXmlDocument(); - /// Create a document with a name. The name of the document is also the filename of the xml. - TiXmlDocument( const char * documentName ); - - #ifdef TIXML_USE_STL - /// Constructor. - TiXmlDocument( const std::string& documentName ); - #endif - - TiXmlDocument( const TiXmlDocument& copy ); - TiXmlDocument& operator=( const TiXmlDocument& copy ); - - virtual ~TiXmlDocument() {} - - /** Load a file using the current document value. - Returns true if successful. Will delete any existing - document data before loading. - */ - bool LoadFile( TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); - /// Save a file using the current document value. Returns true if successful. - bool SaveFile() const; - /// Load a file using the given filename. Returns true if successful. - bool LoadFile( const char * filename, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); - /// Save a file using the given filename. Returns true if successful. - bool SaveFile( const char * filename ) const; - /** Load a file using the given FILE*. Returns true if successful. Note that this method - doesn't stream - the entire object pointed at by the FILE* - will be interpreted as an XML file. TinyXML doesn't stream in XML from the current - file location. Streaming may be added in the future. - */ - bool LoadFile( FILE*, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); - /// Save a file using the given FILE*. Returns true if successful. - bool SaveFile( FILE* ) const; - - #ifdef TIXML_USE_STL - bool LoadFile( const std::string& filename, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ) ///< STL std::string version. - { - return LoadFile( filename.c_str(), encoding ); - } - bool SaveFile( const std::string& filename ) const ///< STL std::string version. - { - return SaveFile( filename.c_str() ); - } - #endif - - /** Parse the given null terminated block of xml data. Passing in an encoding to this - method (either TIXML_ENCODING_LEGACY or TIXML_ENCODING_UTF8 will force TinyXml - to use that encoding, regardless of what TinyXml might otherwise try to detect. - */ - virtual const char* Parse( const char* p, TiXmlParsingData* data = 0, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); - - /** Get the root element -- the only top level element -- of the document. - In well formed XML, there should only be one. TinyXml is tolerant of - multiple elements at the document level. - */ - const TiXmlElement* RootElement() const { return FirstChildElement(); } - TiXmlElement* RootElement() { return FirstChildElement(); } - - /** If an error occurs, Error will be set to true. Also, - - The ErrorId() will contain the integer identifier of the error (not generally useful) - - The ErrorDesc() method will return the name of the error. (very useful) - - The ErrorRow() and ErrorCol() will return the location of the error (if known) - */ - bool Error() const { return error; } - - /// Contains a textual (english) description of the error if one occurs. - const char * ErrorDesc() const { return errorDesc.c_str (); } - - /** Generally, you probably want the error string ( ErrorDesc() ). But if you - prefer the ErrorId, this function will fetch it. - */ - int ErrorId() const { return errorId; } - - /** Returns the location (if known) of the error. The first column is column 1, - and the first row is row 1. A value of 0 means the row and column wasn't applicable - (memory errors, for example, have no row/column) or the parser lost the error. (An - error in the error reporting, in that case.) - - @sa SetTabSize, Row, Column - */ - int ErrorRow() const { return errorLocation.row+1; } - int ErrorCol() const { return errorLocation.col+1; } ///< The column where the error occured. See ErrorRow() - - /** SetTabSize() allows the error reporting functions (ErrorRow() and ErrorCol()) - to report the correct values for row and column. It does not change the output - or input in any way. - - By calling this method, with a tab size - greater than 0, the row and column of each node and attribute is stored - when the file is loaded. Very useful for tracking the DOM back in to - the source file. - - The tab size is required for calculating the location of nodes. If not - set, the default of 4 is used. The tabsize is set per document. Setting - the tabsize to 0 disables row/column tracking. - - Note that row and column tracking is not supported when using operator>>. - - The tab size needs to be enabled before the parse or load. Correct usage: - @verbatim - TiXmlDocument doc; - doc.SetTabSize( 8 ); - doc.Load( "myfile.xml" ); - @endverbatim - - @sa Row, Column - */ - void SetTabSize( int _tabsize ) { tabsize = _tabsize; } - - int TabSize() const { return tabsize; } - - /** If you have handled the error, it can be reset with this call. The error - state is automatically cleared if you Parse a new XML block. - */ - void ClearError() { error = false; - errorId = 0; - errorDesc = ""; - errorLocation.row = errorLocation.col = 0; - //errorLocation.last = 0; - } - - /** Write the document to standard out using formatted printing ("pretty print"). */ - void Print() const { Print( stdout, 0 ); } - - /* Write the document to a string using formatted printing ("pretty print"). This - will allocate a character array (new char[]) and return it as a pointer. The - calling code pust call delete[] on the return char* to avoid a memory leak. - */ - //char* PrintToMemory() const; - - /// Print this Document to a FILE stream. - virtual void Print( FILE* cfile, int depth = 0 ) const; - // [internal use] - void SetError( int err, const char* errorLocation, TiXmlParsingData* prevData, TiXmlEncoding encoding ); - - virtual const TiXmlDocument* ToDocument() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlDocument* ToDocument() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* content ) const; - -protected : - // [internal use] - virtual TiXmlNode* Clone() const; - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - -private: - void CopyTo( TiXmlDocument* target ) const; - - bool error; - int errorId; - TIXML_STRING errorDesc; - int tabsize; - TiXmlCursor errorLocation; - bool useMicrosoftBOM; // the UTF-8 BOM were found when read. Note this, and try to write. -}; - - -/** - A TiXmlHandle is a class that wraps a node pointer with null checks; this is - an incredibly useful thing. Note that TiXmlHandle is not part of the TinyXml - DOM structure. It is a separate utility class. - - Take an example: - @verbatim - - - - - - - @endverbatim - - Assuming you want the value of "attributeB" in the 2nd "Child" element, it's very - easy to write a *lot* of code that looks like: - - @verbatim - TiXmlElement* root = document.FirstChildElement( "Document" ); - if ( root ) - { - TiXmlElement* element = root->FirstChildElement( "Element" ); - if ( element ) - { - TiXmlElement* child = element->FirstChildElement( "Child" ); - if ( child ) - { - TiXmlElement* child2 = child->NextSiblingElement( "Child" ); - if ( child2 ) - { - // Finally do something useful. - @endverbatim - - And that doesn't even cover "else" cases. TiXmlHandle addresses the verbosity - of such code. A TiXmlHandle checks for null pointers so it is perfectly safe - and correct to use: - - @verbatim - TiXmlHandle docHandle( &document ); - TiXmlElement* child2 = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).Child( "Child", 1 ).ToElement(); - if ( child2 ) - { - // do something useful - @endverbatim - - Which is MUCH more concise and useful. - - It is also safe to copy handles - internally they are nothing more than node pointers. - @verbatim - TiXmlHandle handleCopy = handle; - @endverbatim - - What they should not be used for is iteration: - - @verbatim - int i=0; - while ( true ) - { - TiXmlElement* child = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).Child( "Child", i ).ToElement(); - if ( !child ) - break; - // do something - ++i; - } - @endverbatim - - It seems reasonable, but it is in fact two embedded while loops. The Child method is - a linear walk to find the element, so this code would iterate much more than it needs - to. Instead, prefer: - - @verbatim - TiXmlElement* child = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).FirstChild( "Child" ).ToElement(); - - for( child; child; child=child->NextSiblingElement() ) - { - // do something - } - @endverbatim -*/ -class TiXmlHandle -{ -public: - /// Create a handle from any node (at any depth of the tree.) This can be a null pointer. - TiXmlHandle( TiXmlNode* _node ) { this->node = _node; } - /// Copy constructor - TiXmlHandle( const TiXmlHandle& ref ) { this->node = ref.node; } - TiXmlHandle operator=( const TiXmlHandle& ref ) { if ( &ref != this ) this->node = ref.node; return *this; } - - /// Return a handle to the first child node. - TiXmlHandle FirstChild() const; - /// Return a handle to the first child node with the given name. - TiXmlHandle FirstChild( const char * value ) const; - /// Return a handle to the first child element. - TiXmlHandle FirstChildElement() const; - /// Return a handle to the first child element with the given name. - TiXmlHandle FirstChildElement( const char * value ) const; - - /** Return a handle to the "index" child with the given name. - The first child is 0, the second 1, etc. - */ - TiXmlHandle Child( const char* value, int index ) const; - /** Return a handle to the "index" child. - The first child is 0, the second 1, etc. - */ - TiXmlHandle Child( int index ) const; - /** Return a handle to the "index" child element with the given name. - The first child element is 0, the second 1, etc. Note that only TiXmlElements - are indexed: other types are not counted. - */ - TiXmlHandle ChildElement( const char* value, int index ) const; - /** Return a handle to the "index" child element. - The first child element is 0, the second 1, etc. Note that only TiXmlElements - are indexed: other types are not counted. - */ - TiXmlHandle ChildElement( int index ) const; - - #ifdef TIXML_USE_STL - TiXmlHandle FirstChild( const std::string& _value ) const { return FirstChild( _value.c_str() ); } - TiXmlHandle FirstChildElement( const std::string& _value ) const { return FirstChildElement( _value.c_str() ); } - - TiXmlHandle Child( const std::string& _value, int index ) const { return Child( _value.c_str(), index ); } - TiXmlHandle ChildElement( const std::string& _value, int index ) const { return ChildElement( _value.c_str(), index ); } - #endif - - /** Return the handle as a TiXmlNode. This may return null. - */ - TiXmlNode* ToNode() const { return node; } - /** Return the handle as a TiXmlElement. This may return null. - */ - TiXmlElement* ToElement() const { return ( ( node && node->ToElement() ) ? node->ToElement() : 0 ); } - /** Return the handle as a TiXmlText. This may return null. - */ - TiXmlText* ToText() const { return ( ( node && node->ToText() ) ? node->ToText() : 0 ); } - /** Return the handle as a TiXmlUnknown. This may return null. - */ - TiXmlUnknown* ToUnknown() const { return ( ( node && node->ToUnknown() ) ? node->ToUnknown() : 0 ); } - - /** @deprecated use ToNode. - Return the handle as a TiXmlNode. This may return null. - */ - TiXmlNode* Node() const { return ToNode(); } - /** @deprecated use ToElement. - Return the handle as a TiXmlElement. This may return null. - */ - TiXmlElement* Element() const { return ToElement(); } - /** @deprecated use ToText() - Return the handle as a TiXmlText. This may return null. - */ - TiXmlText* Text() const { return ToText(); } - /** @deprecated use ToUnknown() - Return the handle as a TiXmlUnknown. This may return null. - */ - TiXmlUnknown* Unknown() const { return ToUnknown(); } - -private: - TiXmlNode* node; -}; - - -/** Print to memory functionality. The TiXmlPrinter is useful when you need to: - - -# Print to memory (especially in non-STL mode) - -# Control formatting (line endings, etc.) - - When constructed, the TiXmlPrinter is in its default "pretty printing" mode. - Before calling Accept() you can call methods to control the printing - of the XML document. After TiXmlNode::Accept() is called, the printed document can - be accessed via the CStr(), Str(), and Size() methods. - - TiXmlPrinter uses the Visitor API. - @verbatim - TiXmlPrinter printer; - printer.SetIndent( "\t" ); - - doc.Accept( &printer ); - fprintf( stdout, "%s", printer.CStr() ); - @endverbatim -*/ -class TiXmlPrinter : public TiXmlVisitor -{ -public: - TiXmlPrinter() : depth( 0 ), simpleTextPrint( false ), - buffer(), indent( " " ), lineBreak( "\n" ) {} - - virtual bool VisitEnter( const TiXmlDocument& doc ); - virtual bool VisitExit( const TiXmlDocument& doc ); - - virtual bool VisitEnter( const TiXmlElement& element, const TiXmlAttribute* firstAttribute ); - virtual bool VisitExit( const TiXmlElement& element ); - - virtual bool Visit( const TiXmlDeclaration& declaration ); - virtual bool Visit( const TiXmlText& text ); - virtual bool Visit( const TiXmlComment& comment ); - virtual bool Visit( const TiXmlUnknown& unknown ); - - /** Set the indent characters for printing. By default 4 spaces - but tab (\t) is also useful, or null/empty string for no indentation. - */ - void SetIndent( const char* _indent ) { indent = _indent ? _indent : "" ; } - /// Query the indention string. - const char* Indent() { return indent.c_str(); } - /** Set the line breaking string. By default set to newline (\n). - Some operating systems prefer other characters, or can be - set to the null/empty string for no indenation. - */ - void SetLineBreak( const char* _lineBreak ) { lineBreak = _lineBreak ? _lineBreak : ""; } - /// Query the current line breaking string. - const char* LineBreak() { return lineBreak.c_str(); } - - /** Switch over to "stream printing" which is the most dense formatting without - linebreaks. Common when the XML is needed for network transmission. - */ - void SetStreamPrinting() { indent = ""; - lineBreak = ""; - } - /// Return the result. - const char* CStr() { return buffer.c_str(); } - /// Return the length of the result string. - size_t Size() { return buffer.size(); } - - #ifdef TIXML_USE_STL - /// Return the result. - const std::string& Str() { return buffer; } - #endif - -private: - void DoIndent() { - for( int i=0; i -#include - -#include "tinyxml.h" - -//#define DEBUG_PARSER -#if defined( DEBUG_PARSER ) -# if defined( DEBUG ) && defined( _MSC_VER ) -# include -# define TIXML_LOG OutputDebugString -# else -# define TIXML_LOG printf -# endif -#endif - -// Note tha "PutString" hardcodes the same list. This -// is less flexible than it appears. Changing the entries -// or order will break putstring. -TiXmlBase::Entity TiXmlBase::entity[ TiXmlBase::NUM_ENTITY ] = -{ - { "&", 5, '&' }, - { "<", 4, '<' }, - { ">", 4, '>' }, - { """, 6, '\"' }, - { "'", 6, '\'' } -}; - -// Bunch of unicode info at: -// http://www.unicode.org/faq/utf_bom.html -// Including the basic of this table, which determines the #bytes in the -// sequence from the lead byte. 1 placed for invalid sequences -- -// although the result will be junk, pass it through as much as possible. -// Beware of the non-characters in UTF-8: -// ef bb bf (Microsoft "lead bytes") -// ef bf be -// ef bf bf - -const unsigned char TIXML_UTF_LEAD_0 = 0xefU; -const unsigned char TIXML_UTF_LEAD_1 = 0xbbU; -const unsigned char TIXML_UTF_LEAD_2 = 0xbfU; - -const int TiXmlBase::utf8ByteTable[256] = -{ - // 0 1 2 3 4 5 6 7 8 9 a b c d e f - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x00 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x10 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x20 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x30 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x40 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x50 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x60 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x70 End of ASCII range - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x80 0x80 to 0xc1 invalid - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0x90 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0xa0 - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, // 0xb0 - 1, 1, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, // 0xc0 0xc2 to 0xdf 2 byte - 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, // 0xd0 - 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, // 0xe0 0xe0 to 0xef 3 byte - 4, 4, 4, 4, 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 // 0xf0 0xf0 to 0xf4 4 byte, 0xf5 and higher invalid -}; - - -void TiXmlBase::ConvertUTF32ToUTF8( unsigned long input, char* output, int* length ) -{ - const unsigned long BYTE_MASK = 0xBF; - const unsigned long BYTE_MARK = 0x80; - const unsigned long FIRST_BYTE_MARK[7] = { 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC }; - - if (input < 0x80) - *length = 1; - else if ( input < 0x800 ) - *length = 2; - else if ( input < 0x10000 ) - *length = 3; - else if ( input < 0x200000 ) - *length = 4; - else - { *length = 0; return; } // This code won't covert this correctly anyway. - - output += *length; - - // Scary scary fall throughs. - #ifndef _WIN32 - #pragma GCC diagnostic ignored "-Wswitch-default" - #endif - switch (*length) - { - case 4: - --output; - *output = (char)((input | BYTE_MARK) & BYTE_MASK); - input >>= 6; - case 3: - --output; - *output = (char)((input | BYTE_MARK) & BYTE_MASK); - input >>= 6; - case 2: - --output; - *output = (char)((input | BYTE_MARK) & BYTE_MASK); - input >>= 6; - case 1: - --output; - *output = (char)(input | FIRST_BYTE_MARK[*length]); - } - #ifndef _WIN32 - #pragma GCC diagnostic pop - #endif -} - - -/*static*/ int TiXmlBase::IsAlpha( unsigned char anyByte, TiXmlEncoding /*encoding*/ ) -{ - // This will only work for low-ascii, everything else is assumed to be a valid - // letter. I'm not sure this is the best approach, but it is quite tricky trying - // to figure out alhabetical vs. not across encoding. So take a very - // conservative approach. - -// if ( encoding == TIXML_ENCODING_UTF8 ) -// { - if ( anyByte < 127 ) - return isalpha( anyByte ); - else - return 1; // What else to do? The unicode set is huge...get the english ones right. -// } -// else -// { -// return isalpha( anyByte ); -// } -} - - -/*static*/ int TiXmlBase::IsAlphaNum( unsigned char anyByte, TiXmlEncoding /*encoding*/ ) -{ - // This will only work for low-ascii, everything else is assumed to be a valid - // letter. I'm not sure this is the best approach, but it is quite tricky trying - // to figure out alhabetical vs. not across encoding. So take a very - // conservative approach. - -// if ( encoding == TIXML_ENCODING_UTF8 ) -// { - if ( anyByte < 127 ) - return isalnum( anyByte ); - else - return 1; // What else to do? The unicode set is huge...get the english ones right. -// } -// else -// { -// return isalnum( anyByte ); -// } -} - - -class TiXmlParsingData -{ - friend class TiXmlDocument; - public: - void Stamp( const char* now, TiXmlEncoding encoding ); - - const TiXmlCursor& Cursor() const { return cursor; } - - private: - // Only used by the document! - TiXmlParsingData( const char* start, int _tabsize, int row, int col ) - { - assert( start ); - stamp = start; - tabsize = _tabsize; - cursor.row = row; - cursor.col = col; - } - - TiXmlCursor cursor; - const char* stamp; - int tabsize; -}; - - -void TiXmlParsingData::Stamp( const char* now, TiXmlEncoding encoding ) -{ - assert( now ); - - // Do nothing if the tabsize is 0. - if ( tabsize < 1 ) - { - return; - } - - // Get the current row, column. - int row = cursor.row; - int col = cursor.col; - const char* p = stamp; - assert( p ); - - while ( p < now ) - { - // Treat p as unsigned, so we have a happy compiler. - const unsigned char* pU = (const unsigned char*)p; - - // Code contributed by Fletcher Dunn: (modified by lee) - switch (*pU) { - case 0: - // We *should* never get here, but in case we do, don't - // advance past the terminating null character, ever - return; - - case '\r': - // bump down to the next line - ++row; - col = 0; - // Eat the character - ++p; - - // Check for \r\n sequence, and treat this as a single character - if (*p == '\n') { - ++p; - } - break; - - case '\n': - // bump down to the next line - ++row; - col = 0; - - // Eat the character - ++p; - - // Check for \n\r sequence, and treat this as a single - // character. (Yes, this bizarre thing does occur still - // on some arcane platforms...) - if (*p == '\r') { - ++p; - } - break; - - case '\t': - // Eat the character - ++p; - - // Skip to next tab stop - col = (col / tabsize + 1) * tabsize; - break; - - case TIXML_UTF_LEAD_0: - if ( encoding == TIXML_ENCODING_UTF8 ) - { - if ( *(p+1) && *(p+2) ) - { - // In these cases, don't advance the column. These are - // 0-width spaces. - if ( *(pU+1)==TIXML_UTF_LEAD_1 && *(pU+2)==TIXML_UTF_LEAD_2 ) - p += 3; - else if ( *(pU+1)==0xbfU && *(pU+2)==0xbeU ) - p += 3; - else if ( *(pU+1)==0xbfU && *(pU+2)==0xbfU ) - p += 3; - else - { p +=3; ++col; } // A normal character. - } - } - else - { - ++p; - ++col; - } - break; - - default: - if ( encoding == TIXML_ENCODING_UTF8 ) - { - // Eat the 1 to 4 byte utf8 character. - int step = TiXmlBase::utf8ByteTable[*((const unsigned char*)p)]; - if ( step == 0 ) - step = 1; // Error case from bad encoding, but handle gracefully. - p += step; - - // Just advance one column, of course. - ++col; - } - else - { - ++p; - ++col; - } - break; - } - } - cursor.row = row; - cursor.col = col; - assert( cursor.row >= -1 ); - assert( cursor.col >= -1 ); - stamp = p; - assert( stamp ); -} - - -const char* TiXmlBase::SkipWhiteSpace( const char* p, TiXmlEncoding encoding ) -{ - if ( !p || !*p ) - { - return 0; - } - if ( encoding == TIXML_ENCODING_UTF8 ) - { - while ( *p ) - { - const unsigned char* pU = (const unsigned char*)p; - - // Skip the stupid Microsoft UTF-8 Byte order marks - if ( *(pU+0)==TIXML_UTF_LEAD_0 - && *(pU+1)==TIXML_UTF_LEAD_1 - && *(pU+2)==TIXML_UTF_LEAD_2 ) - { - p += 3; - continue; - } - else if(*(pU+0)==TIXML_UTF_LEAD_0 - && *(pU+1)==0xbfU - && *(pU+2)==0xbeU ) - { - p += 3; - continue; - } - else if(*(pU+0)==TIXML_UTF_LEAD_0 - && *(pU+1)==0xbfU - && *(pU+2)==0xbfU ) - { - p += 3; - continue; - } - - if ( IsWhiteSpace( *p ) ) // Still using old rules for white space. - ++p; - else - break; - } - } - else - { - while ( *p && IsWhiteSpace( *p ) ) - ++p; - } - - return p; -} - -#ifdef TIXML_USE_STL -/*static*/ bool TiXmlBase::StreamWhiteSpace( std::istream * in, TIXML_STRING * tag ) -{ - for( ;; ) - { - if ( !in->good() ) return false; - - int c = in->peek(); - // At this scope, we can't get to a document. So fail silently. - if ( !IsWhiteSpace( c ) || c <= 0 ) - return true; - - *tag += (char) in->get(); - } -} - -/*static*/ bool TiXmlBase::StreamTo( std::istream * in, int character, TIXML_STRING * tag ) -{ - //assert( character > 0 && character < 128 ); // else it won't work in utf-8 - while ( in->good() ) - { - int c = in->peek(); - if ( c == character ) - return true; - if ( c <= 0 ) // Silent failure: can't get document at this scope - return false; - - in->get(); - *tag += (char) c; - } - return false; -} -#endif - -// One of TinyXML's more performance demanding functions. Try to keep the memory overhead down. The -// "assign" optimization removes over 10% of the execution time. -// -const char* TiXmlBase::ReadName( const char* p, TIXML_STRING * name, TiXmlEncoding encoding ) -{ - // Oddly, not supported on some comilers, - //name->clear(); - // So use this: - *name = ""; - assert( p ); - - // Names start with letters or underscores. - // Of course, in unicode, tinyxml has no idea what a letter *is*. The - // algorithm is generous. - // - // After that, they can be letters, underscores, numbers, - // hyphens, or colons. (Colons are valid ony for namespaces, - // but tinyxml can't tell namespaces from names.) - if ( p && *p - && ( IsAlpha( (unsigned char) *p, encoding ) || *p == '_' ) ) - { - const char* start = p; - while( p && *p - && ( IsAlphaNum( (unsigned char ) *p, encoding ) - || *p == '_' - || *p == '-' - || *p == '.' - || *p == ':' ) ) - { - //(*name) += *p; // expensive - ++p; - } - if ( p-start > 0 ) { - name->assign( start, p-start ); - } - return p; - } - return 0; -} - -const char* TiXmlBase::GetEntity( const char* p, char* value, int* length, TiXmlEncoding encoding ) -{ - // Presume an entity, and pull it out. - TIXML_STRING ent; - int i; - *length = 0; - - if ( *(p+1) && *(p+1) == '#' && *(p+2) ) - { - unsigned long ucs = 0; - ptrdiff_t delta = 0; - unsigned mult = 1; - - if ( *(p+2) == 'x' ) - { - // Hexadecimal. - if ( !*(p+3) ) return 0; - - const char* q = p+3; - q = strchr( q, ';' ); - - if ( !q || !*q ) return 0; - - delta = q-p; - --q; - - while ( *q != 'x' ) - { - if ( *q >= '0' && *q <= '9' ) - ucs += mult * (*q - '0'); - else if ( *q >= 'a' && *q <= 'f' ) - ucs += mult * (*q - 'a' + 10); - else if ( *q >= 'A' && *q <= 'F' ) - ucs += mult * (*q - 'A' + 10 ); - else - return 0; - mult *= 16; - --q; - } - } - else - { - // Decimal. - if ( !*(p+2) ) return 0; - - const char* q = p+2; - q = strchr( q, ';' ); - - if ( !q || !*q ) return 0; - - delta = q-p; - --q; - - while ( *q != '#' ) - { - if ( *q >= '0' && *q <= '9' ) - ucs += mult * (*q - '0'); - else - return 0; - mult *= 10; - --q; - } - } - if ( encoding == TIXML_ENCODING_UTF8 ) - { - // convert the UCS to UTF-8 - ConvertUTF32ToUTF8( ucs, value, length ); - } - else - { - *value = (char)ucs; - *length = 1; - } - return p + delta + 1; - } - - // Now try to match it. - for( i=0; iappend( cArr, len ); - } - } - else - { - bool whitespace = false; - - // Remove leading white space: - p = SkipWhiteSpace( p, encoding ); - while ( p && *p - && !StringEqual( p, endTag, caseInsensitive, encoding ) ) - { - if ( *p == '\r' || *p == '\n' ) - { - whitespace = true; - ++p; - } - else if ( IsWhiteSpace( *p ) ) - { - whitespace = true; - ++p; - } - else - { - // If we've found whitespace, add it before the - // new character. Any whitespace just becomes a space. - if ( whitespace ) - { - (*text) += ' '; - whitespace = false; - } - int len; - char cArr[4] = { 0, 0, 0, 0 }; - p = GetChar( p, cArr, &len, encoding ); - if ( len == 1 ) - (*text) += cArr[0]; // more efficient - else - text->append( cArr, len ); - } - } - } - if ( p && *p ) - p += strlen( endTag ); - return ( p && *p ) ? p : 0; -} - -#ifdef TIXML_USE_STL - -void TiXmlDocument::StreamIn( std::istream * in, TIXML_STRING * tag ) -{ - // The basic issue with a document is that we don't know what we're - // streaming. Read something presumed to be a tag (and hope), then - // identify it, and call the appropriate stream method on the tag. - // - // This "pre-streaming" will never read the closing ">" so the - // sub-tag can orient itself. - - if ( !StreamTo( in, '<', tag ) ) - { - SetError( TIXML_ERROR_PARSING_EMPTY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return; - } - - while ( in->good() ) - { - int tagIndex = (int) tag->length(); - while ( in->good() && in->peek() != '>' ) - { - int c = in->get(); - if ( c <= 0 ) - { - SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN ); - break; - } - (*tag) += (char) c; - } - - if ( in->good() ) - { - // We now have something we presume to be a node of - // some sort. Identify it, and call the node to - // continue streaming. - TiXmlNode* node = Identify( tag->c_str() + tagIndex, TIXML_DEFAULT_ENCODING ); - - if ( node ) - { - node->StreamIn( in, tag ); - bool isElement = node->ToElement() != 0; - delete node; - node = 0; - - // If this is the root element, we're done. Parsing will be - // done by the >> operator. - if ( isElement ) - { - return; - } - } - else - { - SetError( TIXML_ERROR, 0, 0, TIXML_ENCODING_UNKNOWN ); - return; - } - } - } - // We should have returned sooner. - SetError( TIXML_ERROR, 0, 0, TIXML_ENCODING_UNKNOWN ); -} - -#endif - -const char* TiXmlDocument::Parse( const char* p, TiXmlParsingData* prevData, TiXmlEncoding encoding ) -{ - ClearError(); - - // Parse away, at the document level. Since a document - // contains nothing but other tags, most of what happens - // here is skipping white space. - if ( !p || !*p ) - { - SetError( TIXML_ERROR_DOCUMENT_EMPTY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return 0; - } - - // Note that, for a document, this needs to come - // before the while space skip, so that parsing - // starts from the pointer we are given. - location.Clear(); - if ( prevData ) - { - location.row = prevData->cursor.row; - location.col = prevData->cursor.col; - } - else - { - location.row = 0; - location.col = 0; - } - TiXmlParsingData data( p, TabSize(), location.row, location.col ); - location = data.Cursor(); - - if ( encoding == TIXML_ENCODING_UNKNOWN ) - { - // Check for the Microsoft UTF-8 lead bytes. - const unsigned char* pU = (const unsigned char*)p; - if ( *(pU+0) && *(pU+0) == TIXML_UTF_LEAD_0 - && *(pU+1) && *(pU+1) == TIXML_UTF_LEAD_1 - && *(pU+2) && *(pU+2) == TIXML_UTF_LEAD_2 ) - { - encoding = TIXML_ENCODING_UTF8; - useMicrosoftBOM = true; - } - } - - p = SkipWhiteSpace( p, encoding ); - if ( !p ) - { - SetError( TIXML_ERROR_DOCUMENT_EMPTY, 0, 0, TIXML_ENCODING_UNKNOWN ); - return 0; - } - - while ( p && *p ) - { - TiXmlNode* node = Identify( p, encoding ); - if ( node ) - { - p = node->Parse( p, &data, encoding ); - LinkEndChild( node ); - } - else - { - break; - } - - // Did we get encoding info? - if ( encoding == TIXML_ENCODING_UNKNOWN - && node->ToDeclaration() ) - { - TiXmlDeclaration* dec = node->ToDeclaration(); - const char* enc = dec->Encoding(); - assert( enc ); - - if ( *enc == 0 ) - encoding = TIXML_ENCODING_UTF8; - else if ( StringEqual( enc, "UTF-8", true, TIXML_ENCODING_UNKNOWN ) ) - encoding = TIXML_ENCODING_UTF8; - else if ( StringEqual( enc, "UTF8", true, TIXML_ENCODING_UNKNOWN ) ) - encoding = TIXML_ENCODING_UTF8; // incorrect, but be nice - else - encoding = TIXML_ENCODING_LEGACY; - } - - p = SkipWhiteSpace( p, encoding ); - } - - // Was this empty? - if ( !firstChild ) { - SetError( TIXML_ERROR_DOCUMENT_EMPTY, 0, 0, encoding ); - return 0; - } - - // All is well. - return p; -} - -void TiXmlDocument::SetError( int err, const char* pError, TiXmlParsingData* data, TiXmlEncoding encoding ) -{ - // The first error in a chain is more accurate - don't set again! - if ( error ) - return; - - assert( err > 0 && err < TIXML_ERROR_STRING_COUNT ); - error = true; - errorId = err; - errorDesc = errorString[ errorId ]; - - errorLocation.Clear(); - if ( pError && data ) - { - data->Stamp( pError, encoding ); - errorLocation = data->Cursor(); - } -} - - -TiXmlNode* TiXmlNode::Identify( const char* p, TiXmlEncoding encoding ) -{ - TiXmlNode* returnNode = 0; - - p = SkipWhiteSpace( p, encoding ); - if( !p || !*p || *p != '<' ) - { - return 0; - } - - p = SkipWhiteSpace( p, encoding ); - - if ( !p || !*p ) - { - return 0; - } - - // What is this thing? - // - Elements start with a letter or underscore, but xml is reserved. - // - Comments: "; - - if ( !StringEqual( p, startTag, false, encoding ) ) - { - if ( document ) - document->SetError( TIXML_ERROR_PARSING_COMMENT, p, data, encoding ); - return 0; - } - p += strlen( startTag ); - - // [ 1475201 ] TinyXML parses entities in comments - // Oops - ReadText doesn't work, because we don't want to parse the entities. - // p = ReadText( p, &value, false, endTag, false, encoding ); - // - // from the XML spec: - /* - [Definition: Comments may appear anywhere in a document outside other markup; in addition, - they may appear within the document type declaration at places allowed by the grammar. - They are not part of the document's character data; an XML processor MAY, but need not, - make it possible for an application to retrieve the text of comments. For compatibility, - the string "--" (double-hyphen) MUST NOT occur within comments.] Parameter entity - references MUST NOT be recognized within comments. - - An example of a comment: - - - */ - - value = ""; - // Keep all the white space. - while ( p && *p && !StringEqual( p, endTag, false, encoding ) ) - { - value.append( p, 1 ); - ++p; - } - if ( p && *p ) - p += strlen( endTag ); - - return p; -} - - -const char* TiXmlAttribute::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ) -{ - p = SkipWhiteSpace( p, encoding ); - if ( !p || !*p ) return 0; - - if ( data ) - { - data->Stamp( p, encoding ); - location = data->Cursor(); - } - // Read the name, the '=' and the value. - const char* pErr = p; - p = ReadName( p, &name, encoding ); - if ( !p || !*p ) - { - if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, pErr, data, encoding ); - return 0; - } - p = SkipWhiteSpace( p, encoding ); - if ( !p || !*p || *p != '=' ) - { - if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, p, data, encoding ); - return 0; - } - - ++p; // skip '=' - p = SkipWhiteSpace( p, encoding ); - if ( !p || !*p ) - { - if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, p, data, encoding ); - return 0; - } - - const char* end; - const char SINGLE_QUOTE = '\''; - const char DOUBLE_QUOTE = '\"'; - - if ( *p == SINGLE_QUOTE ) - { - ++p; - end = "\'"; // single quote in string - p = ReadText( p, &value, false, end, false, encoding ); - } - else if ( *p == DOUBLE_QUOTE ) - { - ++p; - end = "\""; // double quote in string - p = ReadText( p, &value, false, end, false, encoding ); - } - else - { - // All attribute values should be in single or double quotes. - // But this is such a common error that the parser will try - // its best, even without them. - value = ""; - while ( p && *p // existence - && !IsWhiteSpace( *p ) // whitespace - && *p != '/' && *p != '>' ) // tag end - { - if ( *p == SINGLE_QUOTE || *p == DOUBLE_QUOTE ) { - // [ 1451649 ] Attribute values with trailing quotes not handled correctly - // We did not have an opening quote but seem to have a - // closing one. Give up and throw an error. - if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, p, data, encoding ); - return 0; - } - value += *p; - ++p; - } - } - return p; -} - -#ifdef TIXML_USE_STL -void TiXmlText::StreamIn( std::istream * in, TIXML_STRING * tag ) -{ - while ( in->good() ) - { - int c = in->peek(); - if ( !cdata && (c == '<' ) ) - { - return; - } - if ( c <= 0 ) - { - TiXmlDocument* document = GetDocument(); - if ( document ) - document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN ); - return; - } - - (*tag) += (char) c; - in->get(); // "commits" the peek made above - - if ( cdata && c == '>' && tag->size() >= 3 ) { - size_t len = tag->size(); - if ( (*tag)[len-2] == ']' && (*tag)[len-3] == ']' ) { - // terminator of cdata. - return; - } - } - } -} -#endif - -const char* TiXmlText::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ) -{ - value = ""; - TiXmlDocument* document = GetDocument(); - - if ( data ) - { - data->Stamp( p, encoding ); - location = data->Cursor(); - } - - const char* const startTag = ""; - - if ( cdata || StringEqual( p, startTag, false, encoding ) ) - { - cdata = true; - - if ( !StringEqual( p, startTag, false, encoding ) ) - { - if ( document ) - document->SetError( TIXML_ERROR_PARSING_CDATA, p, data, encoding ); - return 0; - } - p += strlen( startTag ); - - // Keep all the white space, ignore the encoding, etc. - while ( p && *p - && !StringEqual( p, endTag, false, encoding ) - ) - { - value += *p; - ++p; - } - - TIXML_STRING dummy; - p = ReadText( p, &dummy, false, endTag, false, encoding ); - return p; - } - else - { - bool ignoreWhite = true; - - const char* end = "<"; - p = ReadText( p, &value, ignoreWhite, end, false, encoding ); - if ( p && *p ) - return p-1; // don't truncate the '<' - return 0; - } -} - -#ifdef TIXML_USE_STL -void TiXmlDeclaration::StreamIn( std::istream * in, TIXML_STRING * tag ) -{ - while ( in->good() ) - { - int c = in->get(); - if ( c <= 0 ) - { - TiXmlDocument* document = GetDocument(); - if ( document ) - document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN ); - return; - } - (*tag) += (char) c; - - if ( c == '>' ) - { - // All is well. - return; - } - } -} -#endif - -const char* TiXmlDeclaration::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding _encoding ) -{ - p = SkipWhiteSpace( p, _encoding ); - // Find the beginning, find the end, and look for - // the stuff in-between. - TiXmlDocument* document = GetDocument(); - if ( !p || !*p || !StringEqual( p, "SetError( TIXML_ERROR_PARSING_DECLARATION, 0, 0, _encoding ); - return 0; - } - if ( data ) - { - data->Stamp( p, _encoding ); - location = data->Cursor(); - } - p += 5; - - version = ""; - encoding = ""; - standalone = ""; - - while ( p && *p ) - { - if ( *p == '>' ) - { - ++p; - return p; - } - - p = SkipWhiteSpace( p, _encoding ); - if ( StringEqual( p, "version", true, _encoding ) ) - { - TiXmlAttribute attrib; - p = attrib.Parse( p, data, _encoding ); - version = attrib.Value(); - } - else if ( StringEqual( p, "encoding", true, _encoding ) ) - { - TiXmlAttribute attrib; - p = attrib.Parse( p, data, _encoding ); - encoding = attrib.Value(); - } - else if ( StringEqual( p, "standalone", true, _encoding ) ) - { - TiXmlAttribute attrib; - p = attrib.Parse( p, data, _encoding ); - standalone = attrib.Value(); - } - else - { - // Read over whatever it is. - while( p && *p && *p != '>' && !IsWhiteSpace( *p ) ) - ++p; - } - } - return 0; -} - -bool TiXmlText::Blank() const -{ - for ( unsigned i=0; i