ros_field.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright 2016-2017 Davide Faconti
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of Willow Garage, Inc. nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 * *******************************************************************/
00034 
00035 #include "ros_type_introspection/ros_field.hpp"
00036 #include <boost/regex.hpp>
00037 #include <boost/algorithm/string/regex.hpp>
00038 #include <boost/algorithm/string/trim.hpp>
00039 
00040 namespace RosIntrospection{
00041 
00042 ROSField::ROSField(const std::string &definition):
00043   _array_size(1)
00044 {
00045   static const  boost::regex type_regex("[a-zA-Z][a-zA-Z0-9_]*"
00046                                         "(/[a-zA-Z][a-zA-Z0-9_]*){0,1}"
00047                                         "(\\[[0-9]*\\]){0,1}");
00048 
00049   static const  boost::regex field_regex("[a-zA-Z][a-zA-Z0-9_]*");
00050 
00051   static const boost::regex array_regex("(.+)(\\[([0-9]*)\\])");
00052 
00053   using boost::regex;
00054   std::string::const_iterator begin = definition.begin();
00055   std::string::const_iterator end   = definition.end();
00056   boost::match_results<std::string::const_iterator> what;
00057 
00058   // Get type and field
00059   std::string type, value;
00060 
00061   //-------------------------------
00062   // Find type, field and array size
00063   if( regex_search(begin, end, what, type_regex)) {
00064     type = what[0];
00065     begin = what[0].second;
00066   }
00067   else {
00068     throw std::runtime_error("Bad type when parsing field: " + definition);
00069   }
00070 
00071   if (regex_search(begin, end, what, field_regex))
00072   {
00073     _fieldname = what[0];
00074     begin = what[0].second;
00075   }
00076   else {
00077     throw std::runtime_error("Bad field when parsing field: " + definition);
00078   }
00079 
00080   std::string temp_type = type;
00081   if (regex_search(temp_type, what, array_regex))
00082   {
00083     type = what[1];
00084 
00085     if (what.size() == 3) {
00086       _array_size = -1;
00087     }
00088     else if (what.size() == 4) {
00089       std::string size(what[3].first, what[3].second);
00090       _array_size = size.empty() ? -1 : atoi(size.c_str());
00091     }
00092     else {
00093       throw std::runtime_error("Bad array size when parsing field:  " + definition);
00094     }
00095   }
00096 
00097   //-------------------------------
00098   // Find if Constant or comment
00099 
00100   // Determine next character
00101   // if '=' -> constant, if '#' -> done, if nothing -> done, otherwise error
00102   if (regex_search(begin, end, what, boost::regex("\\S")))
00103   {
00104     if (what[0] == "=")
00105     {
00106       begin = what[0].second;
00107       // Copy constant
00108       if (type == "string") {
00109         value.assign(begin, end);
00110       }
00111       else {
00112         if (regex_search(begin, end, what, boost::regex("\\s*#")))
00113         {
00114           value.assign(begin, what[0].first);
00115         }
00116         else {
00117           value.assign(begin, end);
00118         }
00119         // TODO: Raise error if string is not numeric
00120       }
00121 
00122       boost::algorithm::trim(value);
00123     } else if (what[0] == "#") {
00124       // Ignore comment
00125     } else {
00126       // Error
00127       throw std::runtime_error("Unexpected character after type and field:  " +
00128                                definition);
00129     }
00130   }
00131   _type  = ROSType( type );
00132   _value = value;
00133 }
00134 
00135 }


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Tue May 14 2019 02:49:42