1
1
/*
2
- * Copyright (C) 2018-2022 Michael Ferguson
2
+ * Copyright (C) 2018-2023 Michael Ferguson
3
3
* Copyright (C) 2013-2014 Unbounded Robotics Inc.
4
4
*
5
5
* Licensed under the Apache License, Version 2.0 (the "License");
18
18
// Author: Michael Ferguson
19
19
20
20
#include < fstream>
21
+ #include < iostream>
21
22
#include < string>
22
23
#include < map>
23
- #include < tinyxml .h>
24
+ #include < tinyxml2 .h>
24
25
#include < boost/algorithm/string.hpp>
25
26
#include < boost/lexical_cast.hpp>
26
27
#include < robot_calibration/optimization/offsets.hpp>
@@ -221,10 +222,10 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
221
222
{
222
223
const double precision = 8 ;
223
224
224
- TiXmlDocument xml_doc;
225
+ tinyxml2::XMLDocument xml_doc;
225
226
xml_doc.Parse (urdf.c_str ());
226
227
227
- TiXmlElement *robot_xml = xml_doc.FirstChildElement (" robot" );
228
+ tinyxml2::XMLElement *robot_xml = xml_doc.FirstChildElement (" robot" );
228
229
if (!robot_xml)
229
230
{
230
231
// TODO: error notification? We should never get here since URDF parse
@@ -233,15 +234,16 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
233
234
}
234
235
235
236
// 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" ))
237
239
{
238
240
const char * name = joint_xml->Attribute (" name" );
239
241
240
242
// Is there a joint calibration needed?
241
243
double offset = get (std::string (name));
242
244
if (offset != 0.0 )
243
245
{
244
- TiXmlElement *calibration_xml = joint_xml->FirstChildElement (" calibration" );
246
+ tinyxml2::XMLElement *calibration_xml = joint_xml->FirstChildElement (" calibration" );
245
247
if (calibration_xml)
246
248
{
247
249
// Existing calibration, update rising attribute
@@ -251,7 +253,7 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
251
253
try
252
254
{
253
255
offset += double (boost::lexical_cast<double >(rising_position_str));
254
- calibration_xml->SetDoubleAttribute (" rising" , offset);
256
+ calibration_xml->SetAttribute (" rising" , offset);
255
257
}
256
258
catch (boost::bad_lexical_cast &e)
257
259
{
@@ -266,10 +268,8 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
266
268
else
267
269
{
268
270
// 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);
273
273
}
274
274
}
275
275
@@ -283,7 +283,7 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
283
283
// String streams for output
284
284
std::stringstream xyz_ss, rpy_ss;
285
285
286
- TiXmlElement *origin_xml = joint_xml->FirstChildElement (" origin" );
286
+ tinyxml2::XMLElement *origin_xml = joint_xml->FirstChildElement (" origin" );
287
287
if (origin_xml)
288
288
{
289
289
// Update existing origin
@@ -336,8 +336,8 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
336
336
}
337
337
338
338
// 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 () );
341
341
}
342
342
else
343
343
{
@@ -349,7 +349,7 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
349
349
frame_offset.M .GetRPY (rpy[0 ], rpy[1 ], rpy[2 ]);
350
350
351
351
// No existing origin, create an element with attributes
352
- origin_xml = new TiXmlElement (" origin" );
352
+ origin_xml = joint_xml-> InsertNewChildElement (" origin" );
353
353
354
354
// Create xyz
355
355
for (int i = 0 ; i < 3 ; ++i)
@@ -358,7 +358,7 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
358
358
xyz_ss << " " ;
359
359
xyz_ss << std::fixed << std::setprecision (precision) << xyz[i];
360
360
}
361
- origin_xml->SetAttribute (" xyz" , xyz_ss.str ());
361
+ origin_xml->SetAttribute (" xyz" , xyz_ss.str (). c_str () );
362
362
363
363
// Create rpy
364
364
for (int i = 0 ; i < 3 ; ++i)
@@ -367,18 +367,14 @@ std::string OptimizationOffsets::updateURDF(const std::string &urdf)
367
367
rpy_ss << " " ;
368
368
rpy_ss << std::fixed << std::setprecision (precision) << rpy[i];
369
369
}
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 ());
374
371
}
375
372
}
376
373
}
377
374
378
375
// Print to a string
379
- TiXmlPrinter printer;
380
- printer.SetIndent (" " );
381
- xml_doc.Accept (&printer);
376
+ tinyxml2::XMLPrinter printer;
377
+ xml_doc.Print (&printer);
382
378
std::string new_urdf = printer.CStr ();
383
379
384
380
return new_urdf;
0 commit comments