Skip to content

Commit a3d0185

Browse files
authored
update to tinyxml2 (#159)
* proper depends, rather than hijacking urdfdom * less control over formatting, had to update tests
1 parent 8a1dc42 commit a3d0185

File tree

4 files changed

+48
-49
lines changed

4 files changed

+48
-49
lines changed

Diff for: robot_calibration/CMakeLists.txt

+4-3
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,9 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
1515
add_compile_options(-Wall -Wextra -Wpedantic)
1616
endif()
1717

18+
find_package(tinyxml2_vendor QUIET)
19+
find_package(TinyXML2)
20+
1821
find_package(orocos_kdl REQUIRED)
1922
find_package(ament_cmake REQUIRED)
2023
find_package(camera_calibration_parsers REQUIRED)
@@ -46,6 +49,7 @@ include_directories(include
4649
${EIGEN3_INCLUDE_DIRS}
4750
${orocos_kdl_INCLUDE_DIRS})
4851
link_directories(${orocos_kdl_LIBRARY_DIRS}) # this is a hack, will eventually be unneeded once orocos-kdl is fixed
52+
link_libraries(tinyxml2::tinyxml2)
4953

5054
set(dependencies
5155
camera_calibration_parsers
@@ -84,7 +88,6 @@ add_library(robot_calibration SHARED
8488
target_link_libraries(robot_calibration
8589
${Boost_LIBRARIES}
8690
${CERES_LIBRARIES}
87-
${tinyxml_LIBRARIES}
8891
${orocos_kdl_LIBRARIES}
8992
)
9093
ament_target_dependencies(robot_calibration
@@ -101,7 +104,6 @@ add_library(robot_calibration_feature_finders SHARED
101104
target_link_libraries(robot_calibration_feature_finders
102105
robot_calibration
103106
${Boost_LIBRARIES}
104-
${tinyxml_LIBRARIES}
105107
${orocos_kdl_LIBRARIES}
106108
${OpenCV_LIBS}
107109
)
@@ -114,7 +116,6 @@ target_link_libraries(calibrate
114116
robot_calibration
115117
${Boost_LIBRARIES}
116118
${CERES_LIBRARIES}
117-
${tinyxml_LIBRARIES}
118119
${orocos_kdl_LIBRARIES}
119120
${OpenCV_LIBS}
120121
)

Diff for: robot_calibration/package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@
3333
<depend>std_msgs</depend>
3434
<depend>tf2_geometry_msgs</depend>
3535
<depend>tf2_ros</depend>
36+
<depend>tinyxml2</depend>
37+
<depend>tinyxml2_vendor</depend>
3638
<depend>visualization_msgs</depend>
3739
<depend>libceres-dev</depend>
3840
<depend>libgflags-dev</depend>

Diff for: robot_calibration/src/optimization/offsets.cpp

+19-23
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/*
2-
* Copyright (C) 2018-2022 Michael Ferguson
2+
* Copyright (C) 2018-2023 Michael Ferguson
33
* Copyright (C) 2013-2014 Unbounded Robotics Inc.
44
*
55
* Licensed under the Apache License, Version 2.0 (the "License");
@@ -18,9 +18,10 @@
1818
// Author: Michael Ferguson
1919

2020
#include <fstream>
21+
#include <iostream>
2122
#include <string>
2223
#include <map>
23-
#include <tinyxml.h>
24+
#include <tinyxml2.h>
2425
#include <boost/algorithm/string.hpp>
2526
#include <boost/lexical_cast.hpp>
2627
#include <robot_calibration/optimization/offsets.hpp>
@@ -221,10 +222,10 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
221222
{
222223
const double precision = 8;
223224

224-
TiXmlDocument xml_doc;
225+
tinyxml2::XMLDocument xml_doc;
225226
xml_doc.Parse(urdf.c_str());
226227

227-
TiXmlElement *robot_xml = xml_doc.FirstChildElement("robot");
228+
tinyxml2::XMLElement *robot_xml = xml_doc.FirstChildElement("robot");
228229
if (!robot_xml)
229230
{
230231
// TODO: error notification? We should never get here since URDF parse
@@ -233,15 +234,16 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
233234
}
234235

235236
// Update each joint
236-
for (TiXmlElement* joint_xml = robot_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint"))
237+
for (tinyxml2::XMLElement* joint_xml = robot_xml->FirstChildElement("joint"); joint_xml;
238+
joint_xml = joint_xml->NextSiblingElement("joint"))
237239
{
238240
const char * name = joint_xml->Attribute("name");
239241

240242
// Is there a joint calibration needed?
241243
double offset = get(std::string(name));
242244
if (offset != 0.0)
243245
{
244-
TiXmlElement *calibration_xml = joint_xml->FirstChildElement("calibration");
246+
tinyxml2::XMLElement *calibration_xml = joint_xml->FirstChildElement("calibration");
245247
if (calibration_xml)
246248
{
247249
// Existing calibration, update rising attribute
@@ -251,7 +253,7 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
251253
try
252254
{
253255
offset += double(boost::lexical_cast<double>(rising_position_str));
254-
calibration_xml->SetDoubleAttribute("rising", offset);
256+
calibration_xml->SetAttribute("rising", offset);
255257
}
256258
catch (boost::bad_lexical_cast &e)
257259
{
@@ -266,10 +268,8 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
266268
else
267269
{
268270
// No calibration previously, add an element + attribute
269-
calibration_xml = new TiXmlElement("calibration");
270-
calibration_xml->SetDoubleAttribute("rising", offset);
271-
TiXmlNode * calibration = calibration_xml->Clone();
272-
joint_xml->InsertEndChild(*calibration);
271+
calibration_xml = joint_xml->InsertNewChildElement("calibration");
272+
calibration_xml->SetAttribute("rising", offset);
273273
}
274274
}
275275

@@ -283,7 +283,7 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
283283
// String streams for output
284284
std::stringstream xyz_ss, rpy_ss;
285285

286-
TiXmlElement *origin_xml = joint_xml->FirstChildElement("origin");
286+
tinyxml2::XMLElement *origin_xml = joint_xml->FirstChildElement("origin");
287287
if (origin_xml)
288288
{
289289
// Update existing origin
@@ -336,8 +336,8 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
336336
}
337337

338338
// Update xml
339-
origin_xml->SetAttribute("xyz", xyz_ss.str());
340-
origin_xml->SetAttribute("rpy", rpy_ss.str());
339+
origin_xml->SetAttribute("xyz", xyz_ss.str().c_str());
340+
origin_xml->SetAttribute("rpy", rpy_ss.str().c_str());
341341
}
342342
else
343343
{
@@ -349,7 +349,7 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
349349
frame_offset.M.GetRPY(rpy[0], rpy[1], rpy[2]);
350350

351351
// No existing origin, create an element with attributes
352-
origin_xml = new TiXmlElement("origin");
352+
origin_xml = joint_xml->InsertNewChildElement("origin");
353353

354354
// Create xyz
355355
for (int i = 0; i < 3; ++i)
@@ -358,7 +358,7 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
358358
xyz_ss << " ";
359359
xyz_ss << std::fixed << std::setprecision(precision) << xyz[i];
360360
}
361-
origin_xml->SetAttribute("xyz", xyz_ss.str());
361+
origin_xml->SetAttribute("xyz", xyz_ss.str().c_str());
362362

363363
// Create rpy
364364
for (int i = 0; i < 3; ++i)
@@ -367,18 +367,14 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
367367
rpy_ss << " ";
368368
rpy_ss << std::fixed << std::setprecision(precision) << rpy[i];
369369
}
370-
origin_xml->SetAttribute("rpy", rpy_ss.str());
371-
372-
TiXmlNode * origin = origin_xml->Clone();
373-
joint_xml->InsertEndChild(*origin);
370+
origin_xml->SetAttribute("rpy", rpy_ss.str().c_str());
374371
}
375372
}
376373
}
377374

378375
// Print to a string
379-
TiXmlPrinter printer;
380-
printer.SetIndent(" ");
381-
xml_doc.Accept(&printer);
376+
tinyxml2::XMLPrinter printer;
377+
xml_doc.Print(&printer);
382378
std::string new_urdf = printer.CStr();
383379

384380
return new_urdf;

Diff for: robot_calibration/test/optimization_offsets_tests.cpp

+23-23
Original file line numberDiff line numberDiff line change
@@ -31,30 +31,30 @@ std::string robot_description =
3131
"</robot>";
3232

3333
std::string robot_description_updated =
34-
"<?xml version=\"1.0\" ?>\n"
34+
"<?xml version='1.0' ?>\n"
3535
"<robot name=\"test\">\n"
36-
" <link name=\"link_0\" />\n"
37-
" <joint name=\"first_joint\" type=\"fixed\">\n"
38-
" <origin rpy=\"0 0 0\" xyz=\"1 1 1\" />\n"
39-
" <parent link=\"link_0\" />\n"
40-
" <child link=\"link_1\" />\n"
41-
" </joint>\n"
42-
" <link name=\"link_1\" />\n"
43-
" <joint name=\"second_joint\" type=\"revolute\">\n"
44-
" <origin rpy=\"0 0 0\" xyz=\"0 0 0\" />\n"
45-
" <axis xyz=\"0 0 1\" />\n"
46-
" <limit effort=\"30\" lower=\"-1.57\" upper=\"1.57\" velocity=\"0.524\" />\n"
47-
" <parent link=\"link_1\" />\n"
48-
" <child link=\"link_2\" />\n"
49-
" <calibration rising=\"0.245\" />\n"
50-
" </joint>\n"
51-
" <link name=\"link_2\" />\n"
52-
" <joint name=\"third_joint\" type=\"fixed\">\n"
53-
" <origin rpy=\"1.57000000 -1.50000000 0.00000000\" xyz=\"0.00000000 0.00000000 0.05260000\" />\n"
54-
" <parent link=\"link_2\" />\n"
55-
" <child link=\"link_3\" />\n"
56-
" </joint>\n"
57-
" <link name=\"link_3\" />\n"
36+
" <link name=\"link_0\"/>\n"
37+
" <joint name=\"first_joint\" type=\"fixed\">\n"
38+
" <origin rpy=\"0 0 0\" xyz=\"1 1 1\"/>\n"
39+
" <parent link=\"link_0\"/>\n"
40+
" <child link=\"link_1\"/>\n"
41+
" </joint>\n"
42+
" <link name=\"link_1\"/>\n"
43+
" <joint name=\"second_joint\" type=\"revolute\">\n"
44+
" <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>\n"
45+
" <axis xyz=\"0 0 1\"/>\n"
46+
" <limit effort=\"30\" lower=\"-1.57\" upper=\"1.57\" velocity=\"0.524\"/>\n"
47+
" <parent link=\"link_1\"/>\n"
48+
" <child link=\"link_2\"/>\n"
49+
" <calibration rising=\"0.245\"/>\n"
50+
" </joint>\n"
51+
" <link name=\"link_2\"/>\n"
52+
" <joint name=\"third_joint\" type=\"fixed\">\n"
53+
" <origin rpy=\"1.57000000 -1.50000000 0.00000000\" xyz=\"0.00000000 0.00000000 0.05260000\"/>\n"
54+
" <parent link=\"link_2\"/>\n"
55+
" <child link=\"link_3\"/>\n"
56+
" </joint>\n"
57+
" <link name=\"link_3\"/>\n"
5858
"</robot>";
5959

6060
TEST(OptimizationOffsetTests, test_urdf_update)

0 commit comments

Comments
 (0)