Skip to content

Commit

Permalink
Remove rviz_default_plugins dependency on TinyXML (#531)
Browse files Browse the repository at this point in the history
This clears the way for urdf to switch to TinyXML2
Note that internally, urdf was converting the passed XML to a string and reparsing it in the implementation of `urdf::model::initXml`
  • Loading branch information
rotu committed May 19, 2020
1 parent 50e1baa commit 4b4be6e
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 14 deletions.
3 changes: 0 additions & 3 deletions rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,6 @@ find_package(resource_retriever REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tinyxml_vendor REQUIRED)
find_package(TinyXML REQUIRED) # provided by tinyxml_vendor
find_package(urdf REQUIRED)
find_package(visualization_msgs REQUIRED)

Expand Down Expand Up @@ -223,7 +221,6 @@ target_include_directories(rviz_default_plugins PUBLIC
$<INSTALL_INTERFACE:include>
${OGRE_INCLUDE_DIRS}
${Qt5Widgets_INCLUDE_DIRS}
${TinyXML_INCLUDE_DIRS}
)

target_link_libraries(rviz_default_plugins PUBLIC
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,6 @@

#include <QFile> // NOLINT cpplint cannot handle include order here

// TODO(Martin-Idel-SI): Upgrade to tinyxml2 once supported by urdf
#include <tinyxml.h> // NOLINT cpplint cannot handle include order here
#include "urdf/model.h"

#include "tf2_ros/transform_listener.h"
Expand Down Expand Up @@ -250,16 +248,8 @@ void RobotModelDisplay::load_urdf_from_string(const std::string & robot_descript

void RobotModelDisplay::display_urdf_content()
{
TiXmlDocument doc;
doc.Parse(robot_description_.c_str());
if (!doc.RootElement() ) {
clear();
setStatus(StatusProperty::Error, "URDF", "URDF failed XML parse");
return;
}

urdf::Model descr;
if (!descr.initXml(doc.RootElement())) {
if (!descr.initString(robot_description_)) {
clear();
setStatus(StatusProperty::Error, "URDF", "URDF failed Model parse");
return;
Expand Down

0 comments on commit 4b4be6e

Please sign in to comment.