diff --git a/urdf_parser/src/joint.cpp b/urdf_parser/src/joint.cpp
index 670e5912..7668350f 100644
--- a/urdf_parser/src/joint.cpp
+++ b/urdf_parser/src/joint.cpp
@@ -528,7 +528,7 @@ bool exportPose(Pose &pose, tinyxml2::XMLElement* xml);
bool exportJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* xml)
{
- tinyxml2::XMLElement *dynamics_xml = xml->InsertNewChildElement("dynamics");
+ 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);
@@ -537,7 +537,7 @@ bool exportJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* xml)
bool exportJointLimits(JointLimits &jl, tinyxml2::XMLElement* xml)
{
- tinyxml2::XMLElement *limit_xml = xml->InsertNewChildElement("limit");
+ 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());
@@ -548,7 +548,7 @@ bool exportJointLimits(JointLimits &jl, tinyxml2::XMLElement* xml)
bool exportJointSafety(JointSafety &js, tinyxml2::XMLElement* xml)
{
- tinyxml2::XMLElement *safety_xml = xml->InsertNewChildElement("safety_controller");
+ 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());
@@ -561,7 +561,7 @@ bool exportJointCalibration(JointCalibration &jc, tinyxml2::XMLElement* xml)
{
if (jc.falling || jc.rising)
{
- tinyxml2::XMLElement *calibration_xml = xml->InsertNewChildElement("calibration");
+ tinyxml2::XMLElement *calibration_xml = xml->GetDocument()->NewElement("calibration");
if (jc.falling)
calibration_xml->SetAttribute("falling", urdf_export_helpers::values2str(*jc.falling).c_str());
if (jc.rising)
@@ -576,7 +576,7 @@ bool exportJointMimic(JointMimic &jm, tinyxml2::XMLElement* xml)
{
if (!jm.joint_name.empty())
{
- tinyxml2::XMLElement *mimic_xml = xml->InsertNewChildElement("mimic");
+ 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());
@@ -587,7 +587,7 @@ bool exportJointMimic(JointMimic &jm, tinyxml2::XMLElement* xml)
bool exportJoint(Joint &joint, tinyxml2::XMLElement* xml)
{
- tinyxml2::XMLElement * joint_xml = xml->InsertNewChildElement("joint");
+ 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");
@@ -608,17 +608,17 @@ bool exportJoint(Joint &joint, tinyxml2::XMLElement* xml)
exportPose(joint.parent_to_joint_origin_transform, joint_xml);
// axis
- tinyxml2::XMLElement * axis_xml = joint_xml->InsertNewChildElement("axis");
+ tinyxml2::XMLElement * axis_xml = joint_xml->GetDocument()->NewElement("axis");
axis_xml->SetAttribute("xyz", urdf_export_helpers::values2str(joint.axis).c_str());
joint_xml->LinkEndChild(axis_xml);
// parent
- tinyxml2::XMLElement * parent_xml = joint_xml->InsertNewChildElement("parent");
+ tinyxml2::XMLElement * parent_xml = joint_xml->GetDocument()->NewElement("parent");
parent_xml->SetAttribute("link", joint.parent_link_name.c_str());
joint_xml->LinkEndChild(parent_xml);
// child
- tinyxml2::XMLElement * child_xml = joint_xml->InsertNewChildElement("child");
+ tinyxml2::XMLElement * child_xml = joint_xml->GetDocument()->NewElement("child");
child_xml->SetAttribute("link", joint.child_link_name.c_str());
joint_xml->LinkEndChild(child_xml);
diff --git a/urdf_parser/src/link.cpp b/urdf_parser/src/link.cpp
index 49b16121..85dafd44 100644
--- a/urdf_parser/src/link.cpp
+++ b/urdf_parser/src/link.cpp
@@ -490,15 +490,15 @@ bool exportPose(Pose &pose, tinyxml2::XMLElement* xml);
bool exportMaterial(Material &material, tinyxml2::XMLElement *xml)
{
- tinyxml2::XMLElement* material_xml = xml->InsertNewChildElement("material");
+ tinyxml2::XMLElement* material_xml = xml->GetDocument()->NewElement("material");
material_xml->SetAttribute("name", material.name.c_str());
- tinyxml2::XMLElement* texture = material_xml->InsertNewChildElement("texture");
+ tinyxml2::XMLElement* texture = material_xml->GetDocument()->NewElement("texture");
if (!material.texture_filename.empty())
texture->SetAttribute("filename", material.texture_filename.c_str());
material_xml->LinkEndChild(texture);
- tinyxml2::XMLElement* color = material_xml->InsertNewChildElement("color");
+ tinyxml2::XMLElement* color = material_xml->GetDocument()->NewElement("color");
color->SetAttribute("rgba", urdf_export_helpers::values2str(material.color).c_str());
material_xml->LinkEndChild(color);
xml->LinkEndChild(material_xml);
@@ -508,7 +508,7 @@ bool exportMaterial(Material &material, tinyxml2::XMLElement *xml)
bool exportSphere(Sphere &s, tinyxml2::XMLElement *xml)
{
// e.g. add
- tinyxml2::XMLElement *sphere_xml = xml->InsertNewChildElement("sphere");
+ tinyxml2::XMLElement *sphere_xml = xml->GetDocument()->NewElement("sphere");
sphere_xml->SetAttribute("radius", urdf_export_helpers::values2str(s.radius).c_str());
xml->LinkEndChild(sphere_xml);
return true;
@@ -517,7 +517,7 @@ bool exportSphere(Sphere &s, tinyxml2::XMLElement *xml)
bool exportBox(Box &b, tinyxml2::XMLElement *xml)
{
// e.g. add
- tinyxml2::XMLElement *box_xml = xml->InsertNewChildElement("box");
+ tinyxml2::XMLElement *box_xml = xml->GetDocument()->NewElement("box");
box_xml->SetAttribute("size", urdf_export_helpers::values2str(b.dim).c_str());
xml->LinkEndChild(box_xml);
return true;
@@ -526,7 +526,7 @@ bool exportBox(Box &b, tinyxml2::XMLElement *xml)
bool exportCylinder(Cylinder &y, tinyxml2::XMLElement *xml)
{
// e.g. add
- tinyxml2::XMLElement *cylinder_xml = xml->InsertNewChildElement("cylinder");
+ tinyxml2::XMLElement *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);
@@ -536,7 +536,7 @@ bool exportCylinder(Cylinder &y, tinyxml2::XMLElement *xml)
bool exportMesh(Mesh &m, tinyxml2::XMLElement *xml)
{
// e.g. add
- tinyxml2::XMLElement *mesh_xml = xml->InsertNewChildElement("mesh");
+ tinyxml2::XMLElement *mesh_xml = xml->GetDocument()->NewElement("mesh");
if (!m.filename.empty())
mesh_xml->SetAttribute("filename", m.filename.c_str());
mesh_xml->SetAttribute("scale", urdf_export_helpers::values2str(m.scale).c_str());
@@ -546,7 +546,7 @@ bool exportMesh(Mesh &m, tinyxml2::XMLElement *xml)
bool exportGeometry(GeometrySharedPtr &geom, tinyxml2::XMLElement *xml)
{
- tinyxml2::XMLElement *geometry_xml = xml->InsertNewChildElement("geometry");
+ tinyxml2::XMLElement *geometry_xml = xml->GetDocument()->NewElement("geometry");
if (urdf::dynamic_pointer_cast(geom))
{
exportSphere((*(urdf::dynamic_pointer_cast(geom).get())), geometry_xml);
@@ -583,15 +583,15 @@ bool exportInertial(Inertial &i, tinyxml2::XMLElement *xml)
//
//
//
- tinyxml2::XMLElement *inertial_xml = xml->InsertNewChildElement("inertial");
+ tinyxml2::XMLElement *inertial_xml = xml->GetDocument()->NewElement("inertial");
- tinyxml2::XMLElement *mass_xml = inertial_xml->InsertNewChildElement("mass");
+ tinyxml2::XMLElement *mass_xml = inertial_xml->GetDocument()->NewElement("mass");
mass_xml->SetAttribute("value", urdf_export_helpers::values2str(i.mass).c_str());
inertial_xml->LinkEndChild(mass_xml);
exportPose(i.origin, inertial_xml);
- tinyxml2::XMLElement *inertia_xml = inertial_xml->InsertNewChildElement("inertia");
+ tinyxml2::XMLElement *inertia_xml = inertial_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());
@@ -614,7 +614,7 @@ bool exportVisual(Visual &vis, tinyxml2::XMLElement *xml)
//
//
//
- tinyxml2::XMLElement * visual_xml = xml->InsertNewChildElement("visual");
+ tinyxml2::XMLElement * visual_xml = xml->GetDocument()->NewElement("visual");
exportPose(vis.origin, visual_xml);
@@ -637,7 +637,7 @@ bool exportCollision(Collision &col, tinyxml2::XMLElement* xml)
//
//
//
- tinyxml2::XMLElement * collision_xml = xml->InsertNewChildElement("collision");
+ tinyxml2::XMLElement * collision_xml = xml->GetDocument()->NewElement("collision");
exportPose(col.origin, collision_xml);
@@ -650,7 +650,7 @@ bool exportCollision(Collision &col, tinyxml2::XMLElement* xml)
bool exportLink(Link &link, tinyxml2::XMLElement* xml)
{
- tinyxml2::XMLElement * link_xml = xml->InsertNewChildElement("link");
+ tinyxml2::XMLElement * link_xml = xml->GetDocument()->NewElement("link");
link_xml->SetAttribute("name", link.name.c_str());
if (link.inertial)
diff --git a/urdf_parser/src/pose.cpp b/urdf_parser/src/pose.cpp
index 9a39adc5..87479f39 100644
--- a/urdf_parser/src/pose.cpp
+++ b/urdf_parser/src/pose.cpp
@@ -121,7 +121,7 @@ bool parsePose(Pose &pose, tinyxml2::XMLElement* xml)
bool exportPose(Pose &pose, tinyxml2::XMLElement* xml)
{
- tinyxml2::XMLElement* origin = xml->InsertNewChildElement("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.c_str());
diff --git a/urdf_parser/src/world.cpp b/urdf_parser/src/world.cpp
index 2d930e63..4aa6e3a9 100644
--- a/urdf_parser/src/world.cpp
+++ b/urdf_parser/src/world.cpp
@@ -56,7 +56,7 @@ bool parseWorld(World &/*world*/, tinyxml2::XMLElement* /*config*/)
bool exportWorld(World &world, tinyxml2::XMLElement* xml)
{
- tinyxml2::XMLElement * world_xml = xml->InsertNewChildElement("world");
+ tinyxml2::XMLElement * world_xml = xml->GetDocument()->NewElement("world");
world_xml->SetAttribute("name", world.name.c_str());
// to be implemented