1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 *  Copyright (c) 2008, Willow Garage, Inc.
5 *  All rights reserved.
6 *
7 *  Redistribution and use in source and binary forms, with or without
8 *  modification, are permitted provided that the following conditions
9 *  are met:
10 *
11 *   * Redistributions of source code must retain the above copyright
12 *     notice, this list of conditions and the following disclaimer.
13 *   * Redistributions in binary form must reproduce the above
14 *     copyright notice, this list of conditions and the following
15 *     disclaimer in the documentation and/or other materials provided
16 *     with the distribution.
17 *   * Neither the name of the Willow Garage nor the names of its
18 *     contributors may be used to endorse or promote products derived
19 *     from this software without specific prior written permission.
20 *
21 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 *  POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Wim Meeussen, John Hsu */
36 
37 
38 #include <urdf_model/pose.h>
39 #include <fstream>
40 #include <sstream>
41 #include <algorithm>
42 #include <console_bridge/console.h>
43 #include <tinyxml.h>
44 #include <urdf_parser/urdf_parser.h>
45 
46 namespace urdf_export_helpers {
47 
values2str(unsigned int count,const double * values,double (* conv)(double))48 std::string values2str(unsigned int count, const double *values, double (*conv)(double))
49 {
50     std::stringstream ss;
51     for (unsigned int i = 0 ; i < count ; i++)
52     {
53         if (i > 0)
54             ss << " ";
55         ss << (conv ? conv(values[i]) : values[i]);
56     }
57     return ss.str();
58 }
values2str(urdf::Vector3 vec)59 std::string values2str(urdf::Vector3 vec)
60 {
61     double xyz[3];
62     xyz[0] = vec.x;
63     xyz[1] = vec.y;
64     xyz[2] = vec.z;
65     return values2str(3, xyz);
66 }
values2str(urdf::Rotation rot)67 std::string values2str(urdf::Rotation rot)
68 {
69     double rpy[3];
70     rot.getRPY(rpy[0], rpy[1], rpy[2]);
71     return values2str(3, rpy);
72 }
values2str(urdf::Color c)73 std::string values2str(urdf::Color c)
74 {
75     double rgba[4];
76     rgba[0] = c.r;
77     rgba[1] = c.g;
78     rgba[2] = c.b;
79     rgba[3] = c.a;
80     return values2str(4, rgba);
81 }
values2str(double d)82 std::string values2str(double d)
83 {
84     return values2str(1, &d);
85 }
86 }
87 
88 namespace urdf{
89 
parsePose(Pose & pose,TiXmlElement * xml)90 bool parsePose(Pose &pose, TiXmlElement* xml)
91 {
92   pose.clear();
93   if (xml)
94   {
95     const char* xyz_str = xml->Attribute("xyz");
96     if (xyz_str != NULL)
97     {
98       try {
99         pose.position.init(xyz_str);
100       }
101       catch (ParseError &e) {
102         CONSOLE_BRIDGE_logError(e.what());
103         return false;
104       }
105     }
106 
107     const char* rpy_str = xml->Attribute("rpy");
108     if (rpy_str != NULL)
109     {
110       try {
111         pose.rotation.init(rpy_str);
112       }
113       catch (ParseError &e) {
114         CONSOLE_BRIDGE_logError(e.what());
115         return false;
116       }
117     }
118   }
119   return true;
120 }
121 
exportPose(Pose & pose,TiXmlElement * xml)122 bool exportPose(Pose &pose, TiXmlElement* xml)
123 {
124   TiXmlElement *origin = new TiXmlElement("origin");
125   std::string pose_xyz_str = urdf_export_helpers::values2str(pose.position);
126   std::string pose_rpy_str = urdf_export_helpers::values2str(pose.rotation);
127   origin->SetAttribute("xyz", pose_xyz_str);
128   origin->SetAttribute("rpy", pose_rpy_str);
129   xml->LinkEndChild(origin);
130   return true;
131 }
132 
133 }
134 
135 
136