xml_utils.cpp
Go to the documentation of this file.
00001 /*+-------------------------------------------------------------------------+
00002   |                       MultiVehicle simulator (libmvsim)                 |
00003   |                                                                         |
00004   | Copyright (C) 2014  Jose Luis Blanco Claraco (University of Almeria)    |
00005   | Copyright (C) 2017  Borys Tymchenko (Odessa Polytechnic University)     |
00006   | Distributed under GNU General Public License version 3                  |
00007   |   See <http://www.gnu.org/licenses/>                                    |
00008   +-------------------------------------------------------------------------+ */
00009 
00010 #include <mvsim/basic_types.h>
00011 #include "xml_utils.h"
00012 
00013 #include <cstdio>
00014 #include <mrpt/utils/utils_defs.h>
00015 #include <mrpt/utils/TColor.h>
00016 #include <mrpt/poses/CPose2D.h>
00017 #include <mrpt/poses/CPose3D.h>
00018 #include <mrpt/math/lightweight_geom_data.h>
00019 #include <mrpt/system/string_utils.h>
00020 
00021 using namespace rapidxml;
00022 using namespace mvsim;
00023 
00028 void TParamEntry::parse(
00029         const std::string& str, const std::string& varName,
00030         const char* function_name_context) const
00031 {
00032         // Special cases:
00033         // "%s" ==> std::strings
00034         if (std::string(frmt) == std::string("%s"))
00035         {
00036                 char auxStr[512];
00037                 if (1 != ::sscanf(str.c_str(), frmt, auxStr))
00038                         throw std::runtime_error(
00039                                 mrpt::format(
00040                                         "%s Error parsing '%s'='%s' (Expected format:'%s')",
00041                                         function_name_context, varName.c_str(), str.c_str(), frmt));
00042                 std::string& str = *reinterpret_cast<std::string*>(val);
00043                 str = mrpt::system::trim(auxStr);
00044         }
00045         // "%lf_deg" ==> DEG2RAD()
00046         else if (std::string(frmt) == std::string("%lf_deg"))
00047         {
00048                 if (1 != ::sscanf(str.c_str(), frmt, val))
00049                         throw std::runtime_error(
00050                                 mrpt::format(
00051                                         "%s Error parsing attribute '%s'='%s' (Expected "
00052                                         "format:'%s')",
00053                                         function_name_context, varName.c_str(), str.c_str(), frmt));
00054                 double& ang = *reinterpret_cast<double*>(val);
00055                 ang = mrpt::utils::DEG2RAD(ang);
00056         }
00057         // "%bool" ==> bool*
00058         else if (std::string(frmt) == std::string("%bool"))
00059         {
00060                 bool& bool_val = *reinterpret_cast<bool*>(val);
00061 
00062                 const std::string sStr =
00063                         mrpt::system::lowerCase(mrpt::system::trim(std::string(str)));
00064                 if (sStr == "1" || sStr == "true")
00065                         bool_val = true;
00066                 else if (sStr == "0" || sStr == "false")
00067                         bool_val = false;
00068                 else
00069                         throw std::runtime_error(
00070                                 mrpt::format(
00071                                         "%s Error parsing 'bool' attribute '%s'='%s' (Expected "
00072                                         "'true' or 'false')",
00073                                         function_name_context, varName.c_str(), str.c_str()));
00074         }
00075         // "%color" ==> TColor
00076         else if (std::string(frmt) == std::string("%color"))
00077         {
00078                 // HTML-like format:
00079                 if (!(str.size() > 1 && str[0] == '#'))
00080                         throw std::runtime_error(
00081                                 mrpt::format(
00082                                         "%s Error parsing '%s'='%s' (Expected "
00083                                         "format:'#RRGGBB[AA]')",
00084                                         function_name_context, varName.c_str(), str.c_str()));
00085 
00086                 unsigned int r, g, b, a = 0xff;
00087                 int ret = ::sscanf(str.c_str() + 1, "%2x%2x%2x%2x", &r, &g, &b, &a);
00088                 if (ret != 3 && ret != 4)
00089                         throw std::runtime_error(
00090                                 mrpt::format(
00091                                         "%s Error parsing '%s'='%s' (Expected "
00092                                         "format:'#RRGGBB[AA]')",
00093                                         function_name_context, varName.c_str(), str.c_str()));
00094                 mrpt::utils::TColor& col = *reinterpret_cast<mrpt::utils::TColor*>(val);
00095                 col = mrpt::utils::TColor(r, g, b, a);
00096         }
00097         // "%pose2d"
00098         // "%pose2d_ptr3d"
00099         else if (!strncmp(frmt, "%pose2d", strlen("%pose2d")))
00100         {
00101                 double x, y, yaw;
00102                 int ret = ::sscanf(str.c_str(), "%lf %lf %lf", &x, &y, &yaw);
00103                 if (ret != 3)
00104                         throw std::runtime_error(
00105                                 mrpt::format(
00106                                         "%s Error parsing '%s'='%s' (Expected format:'X Y "
00107                                         "YAW_DEG')",
00108                                         function_name_context, varName.c_str(), str.c_str()));
00109 
00110                 // User provides angles in deg:
00111                 yaw = mrpt::utils::DEG2RAD(yaw);
00112 
00113                 const mrpt::poses::CPose2D p(x, y, yaw);
00114 
00115                 // Sub-cases:
00116                 if (!strcmp(frmt, "%pose2d"))
00117                 {
00118                         mrpt::poses::CPose2D& pp =
00119                                 *reinterpret_cast<mrpt::poses::CPose2D*>(val);
00120                         pp = p;
00121                 }
00122                 else if (!strcmp(frmt, "%pose2d_ptr3d"))
00123                 {
00124                         mrpt::poses::CPose3D& pp =
00125                                 *reinterpret_cast<mrpt::poses::CPose3D*>(val);
00126                         pp = mrpt::poses::CPose3D(p);
00127                 }
00128                 else
00129                         throw std::runtime_error(
00130                                 mrpt::format(
00131                                         "%s Error: Unknown format specifier '%s'",
00132                                         function_name_context, frmt));
00133         }
00134         else
00135         {
00136                 // Generic parse:
00137                 if (1 != ::sscanf(str.c_str(), frmt, val))
00138                         throw std::runtime_error(
00139                                 mrpt::format(
00140                                         "%s Error parsing attribute '%s'='%s' (Expected "
00141                                         "format:'%s')",
00142                                         function_name_context, varName.c_str(), str.c_str(), frmt));
00143         }
00144 }
00145 
00146 void mvsim::parse_xmlnode_attribs(
00147         const rapidxml::xml_node<char>& xml_node,
00148         const std::map<std::string, TParamEntry>& params,
00149         const char* function_name_context)
00150 {
00151         for (std::map<std::string, TParamEntry>::const_iterator it = params.begin();
00152                  it != params.end(); ++it)
00153         {
00154                 const rapidxml::xml_attribute<char>* attr =
00155                         xml_node.first_attribute(it->first.c_str());
00156                 if (attr && attr->value())
00157                         it->second.parse(
00158                                 attr->value(), attr->name(), function_name_context);
00159         }
00160 }
00161 
00162 bool mvsim::parse_xmlnode_as_param(
00163         const rapidxml::xml_node<char>& xml_node,
00164         const std::map<std::string, TParamEntry>& params,
00165         const char* function_name_context)
00166 {
00167         std::map<std::string, TParamEntry>::const_iterator it_param =
00168                 params.find(xml_node.name());
00169 
00170         if (it_param != params.end())
00171         {
00172                 // parse parameter:
00173                 it_param->second.parse(
00174                         xml_node.value(), xml_node.name(), function_name_context);
00175                 return true;
00176         }
00177         return false;
00178 }
00179 
00182 void mvsim::parse_xmlnode_children_as_param(
00183         const rapidxml::xml_node<char>& root,
00184         const std::map<std::string, TParamEntry>& params,
00185         const char* function_name_context)
00186 {
00187         rapidxml::xml_node<>* node = root.first_node();
00188         while (node)
00189         {
00190                 parse_xmlnode_as_param(*node, params, function_name_context);
00191                 node = node->next_sibling(NULL);  // Move on to next node
00192         }
00193 }
00194 
00200 vec3 mvsim::parseXYPHI(
00201         const std::string& s, bool allow_missing_angle,
00202         double default_angle_radians)
00203 {
00204         vec3 v;
00205         v.vals[2] = mrpt::utils::RAD2DEG(default_angle_radians);  // Default ang.
00206 
00207         int na =
00208                 ::sscanf(s.c_str(), "%lf %lf %lf", &v.vals[0], &v.vals[1], &v.vals[2]);
00209 
00210         // User provides numbers as degrees:
00211         v.vals[2] = mrpt::utils::DEG2RAD(v.vals[2]);
00212 
00213         if ((na != 3 && !allow_missing_angle) ||
00214                 (na != 2 && na != 3 && allow_missing_angle))
00215                 throw std::runtime_error(
00216                         mrpt::format("Malformed pose string: '%s'", s.c_str()));
00217 
00218         return v;
00219 }
00220 
00225 void mvsim::parse_xmlnode_shape(
00226         const rapidxml::xml_node<char>& xml_node, mrpt::math::TPolygon2D& out_poly,
00227         const char* function_name_context)
00228 {
00229         out_poly.clear();
00230 
00231         for (rapidxml::xml_node<char>* pt_node = xml_node.first_node("pt"); pt_node;
00232                  pt_node = pt_node->next_sibling("pt"))
00233         {
00234                 if (!pt_node->value())
00235                         throw std::runtime_error(
00236                                 mrpt::format(
00237                                         "%s Error: <pt> node seems empty.", function_name_context));
00238 
00239                 mrpt::math::TPoint2D pt;
00240                 const char* str_val = pt_node->value();
00241                 if (2 != ::sscanf(str_val, "%lf %lf", &pt.x, &pt.y))
00242                         throw std::runtime_error(
00243                                 mrpt::format(
00244                                         "%s Error parsing <pt> node: '%s' (Expected format:'<pt>X "
00245                                         "Y</pt>')",
00246                                         function_name_context, str_val));
00247 
00248                 out_poly.push_back(pt);
00249         }
00250 
00251         if (out_poly.size() < 3)
00252                 throw std::runtime_error(
00253                         mrpt::format(
00254                                 "%s Error: <shape> node requires 3 or more <pt>X Y</pt> "
00255                                 "entries.",
00256                                 function_name_context));
00257 }


mvsim
Author(s):
autogenerated on Thu Sep 7 2017 09:27:48