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