Skip to content

Commit

Permalink
convert to tinyxml2 to avoid deprecated interfaces in urdf (#1237)
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood authored May 10, 2018
1 parent d9afa34 commit 40cc286
Show file tree
Hide file tree
Showing 6 changed files with 23 additions and 24 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ else()
set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR})
endif()

find_package(TinyXML REQUIRED)
find_package(TinyXML2 REQUIRED)

catkin_python_setup()

Expand Down Expand Up @@ -213,7 +213,7 @@ include_directories(SYSTEM
${OGRE_OV_INCLUDE_DIRS}
${OPENGL_INCLUDE_DIR}
${PYTHON_INCLUDE_PATH}
${TinyXML_INCLUDE_DIRS}
${TinyXML2_INCLUDE_DIRS}
${urdfdom_headers_INCLUDE_DIRS}
)
include_directories(src ${catkin_INCLUDE_DIRS})
Expand Down
4 changes: 2 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
<build_depend>std_msgs</build_depend>
<build_depend>std_srvs</build_depend>
<build_depend>tf</build_depend>
<build_depend>tinyxml</build_depend>
<build_depend>tinyxml2</build_depend>
<build_depend>urdf</build_depend>
<build_depend>visualization_msgs</build_depend>
<build_depend>yaml-cpp</build_depend>
Expand Down Expand Up @@ -77,7 +77,7 @@
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>tf</run_depend>
<run_depend>tinyxml</run_depend>
<run_depend>tinyxml2</run_depend>
<run_depend>urdf</run_depend>
<run_depend>visualization_msgs</run_depend>
<run_depend>yaml-cpp</run_depend>
Expand Down
2 changes: 1 addition & 1 deletion src/rviz/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ target_link_libraries(${PROJECT_NAME}
${OGRE_OV_LIBRARIES_ABS}
${OPENGL_LIBRARIES}
${rviz_ADDITIONAL_LIBRARIES}
${TinyXML_LIBRARIES}
${TinyXML2_LIBRARIES}
${X11_X11_LIB}
assimp
yaml-cpp
Expand Down
4 changes: 2 additions & 2 deletions src/rviz/default_plugin/robot_model_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#include <OgreSceneNode.h>
#include <OgreSceneManager.h>

#include <tinyxml.h>
#include <tinyxml2.h>
#include <urdf/model.h>

#include <tf/transform_listener.h>
Expand Down Expand Up @@ -174,7 +174,7 @@ void RobotModelDisplay::load()

robot_description_ = content;

TiXmlDocument doc;
tinyxml2::XMLDocument doc;
doc.Parse( robot_description_.c_str() );
if( !doc.RootElement() )
{
Expand Down
20 changes: 10 additions & 10 deletions src/rviz/display_factory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@

#include "rviz/display_factory.h"

#include <tinyxml.h>
#include <tinyxml2.h>

namespace rviz
{
Expand Down Expand Up @@ -75,31 +75,31 @@ QSet<QString> DisplayFactory::getMessageTypes( const QString& class_id )
if ( !xml_file.isEmpty() )
{
ROS_DEBUG_STREAM("Parsing " << xml_file.toStdString());
TiXmlDocument document;
document.LoadFile(xml_file.toStdString());
TiXmlElement * config = document.RootElement();
tinyxml2::XMLDocument document;
document.LoadFile(xml_file.toStdString().c_str());
tinyxml2::XMLElement * config = document.RootElement();
if (config == NULL)
{
ROS_ERROR("Skipping XML Document \"%s\" which had no Root Element. This likely means the XML is malformed or missing.", xml_file.toStdString().c_str());
return QSet<QString>();
}
if (config->ValueStr() != "library" &&
config->ValueStr() != "class_libraries")
if (std::string(config->Name()) != "library" &&
std::string(config->Name()) != "class_libraries")
{
ROS_ERROR("The XML document \"%s\" given to add must have either \"library\" or \
\"class_libraries\" as the root tag", xml_file.toStdString().c_str());
return QSet<QString>();
}
//Step into the filter list if necessary
if (config->ValueStr() == "class_libraries")
if (std::string(config->Name()) == "class_libraries")
{
config = config->FirstChildElement("library");
}

TiXmlElement* library = config;
tinyxml2::XMLElement* library = config;
while ( library != NULL)
{
TiXmlElement* class_element = library->FirstChildElement("class");
tinyxml2::XMLElement* class_element = library->FirstChildElement("class");
while (class_element)
{
std::string derived_class = class_element->Attribute("type");
Expand All @@ -117,7 +117,7 @@ QSet<QString> DisplayFactory::getMessageTypes( const QString& class_id )
}

QSet<QString> message_types;
TiXmlElement* message_type = class_element->FirstChildElement("message_type");
tinyxml2::XMLElement* message_type = class_element->FirstChildElement("message_type");

while ( message_type )
{
Expand Down
13 changes: 6 additions & 7 deletions src/rviz/mesh_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,7 @@
#include <OgreSharedPtr.h>
#include <OgreTechnique.h>

#include <tinyxml.h>

#include <tinyxml2.h>

#include <ros/assert.h>

Expand Down Expand Up @@ -577,7 +576,7 @@ float getMeshUnitRescale(const std::string& resource_path)


// Try to read unit to meter conversion ratio from mesh. Only valid in Collada XML formats.
TiXmlDocument xmlDoc;
tinyxml2::XMLDocument xmlDoc;
float unit_scale(1.0);
resource_retriever::Retriever retriever;
resource_retriever::MemoryResource res;
Expand All @@ -604,19 +603,19 @@ float getMeshUnitRescale(const std::string& resource_path)
// Find the appropriate element if it exists
if(!xmlDoc.Error())
{
TiXmlElement * colladaXml = xmlDoc.FirstChildElement("COLLADA");
tinyxml2::XMLElement * colladaXml = xmlDoc.FirstChildElement("COLLADA");
if(colladaXml)
{
TiXmlElement *assetXml = colladaXml->FirstChildElement("asset");
tinyxml2::XMLElement *assetXml = colladaXml->FirstChildElement("asset");
if(assetXml)
{
TiXmlElement *unitXml = assetXml->FirstChildElement("unit");
tinyxml2::XMLElement *unitXml = assetXml->FirstChildElement("unit");
if (unitXml && unitXml->Attribute("meter"))
{
// Failing to convert leaves unit_scale as the default.
if(unitXml->QueryFloatAttribute("meter", &unit_scale) != 0)
ROS_WARN_STREAM("getMeshUnitRescale::Failed to convert unit element meter attribute to determine scaling. unit element: "
<< *unitXml);
<< unitXml->GetText());
}
}
}
Expand Down

0 comments on commit 40cc286

Please sign in to comment.