parse.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 #ifndef PCL_CONSOLE_PARSE_H_
00039 #define PCL_CONSOLE_PARSE_H_
00040 
00041 #include <vector>
00042 #include <sstream>
00043 #include <pcl/pcl_macros.h>
00044 
00045 namespace pcl
00046 {
00047   namespace console
00048   {
00058     PCL_EXPORTS bool
00059     find_switch (int argc, char** argv, const char* argument_name);
00060 
00067     PCL_EXPORTS int
00068     find_argument (int argc, char** argv, const char* argument_name);
00069 
00077     template<typename Type> int
00078     parse (int argc, char** argv, const char* argument_name, Type& value)
00079     {
00080       int index = find_argument (argc, argv, argument_name) + 1;
00081 
00082       if (index > 0 && index < argc)
00083       {
00084         std::istringstream stream;
00085         stream.clear ();
00086         stream.str (argv[index]);
00087         stream >> value;
00088       }
00089 
00090       return (index - 1);
00091     }
00092 
00100     PCL_EXPORTS int
00101     parse_argument (int argc, char** argv, const char* str, std::string &val);
00102 
00110     PCL_EXPORTS int
00111     parse_argument (int argc, char** argv, const char* str, bool &val);
00112 
00120     PCL_EXPORTS int
00121     parse_argument (int argc, char** argv, const char* str, float &val);
00122     
00130     PCL_EXPORTS int
00131     parse_argument (int argc, char** argv, const char* str, double &val);
00132 
00140     PCL_EXPORTS int
00141     parse_argument (int argc, char** argv, const char* str, int &val);
00142 
00150     PCL_EXPORTS int
00151     parse_argument (int argc, char** argv, const char* str, unsigned int &val);
00152 
00160     PCL_EXPORTS int
00161     parse_argument (int argc, char** argv, const char* str, char &val);
00162 
00172     PCL_EXPORTS int
00173     parse_2x_arguments (int argc, char** argv, const char* str, float &f, float &s, bool debug = true);
00174 
00184     PCL_EXPORTS int
00185     parse_2x_arguments (int argc, char** argv, const char* str, double &f, double &s, bool debug = true);
00186 
00196     PCL_EXPORTS int
00197     parse_2x_arguments (int argc, char** argv, const char* str, int &f, int &s, bool debug = true);
00198 
00209     PCL_EXPORTS int
00210     parse_3x_arguments (int argc, char** argv, const char* str, float &f, float &s, float &t, bool debug = true);
00211 
00222     PCL_EXPORTS int
00223     parse_3x_arguments (int argc, char** argv, const char* str, double &f, double &s, double &t, bool debug = true);
00224 
00235     PCL_EXPORTS int
00236     parse_3x_arguments (int argc, char** argv, const char* str, int &f, int &s, int &t, bool debug = true);
00237 
00245     PCL_EXPORTS int
00246     parse_x_arguments (int argc, char** argv, const char* str, std::vector<double>& v);
00247 
00255     PCL_EXPORTS int
00256     parse_x_arguments (int argc, char** argv, const char* str, std::vector<float>& v);
00257 
00265     PCL_EXPORTS int
00266     parse_x_arguments (int argc, char** argv, const char* str, std::vector<int>& v);
00267 
00275     PCL_EXPORTS bool
00276     parse_multiple_arguments (int argc, char** argv, const char* str, std::vector<int> &values);
00277 
00285     PCL_EXPORTS bool
00286     parse_multiple_arguments (int argc, char** argv, const char* str, std::vector<float> &values);
00287 
00295     PCL_EXPORTS bool
00296     parse_multiple_arguments (int argc, char** argv, const char* str, std::vector<double> &values);
00297 
00305     PCL_EXPORTS bool
00306     parse_multiple_arguments (int argc, char** argv, const char* str, std::vector<std::string> &values);
00307 
00317     PCL_EXPORTS bool
00318     parse_multiple_2x_arguments (int argc, char** argv, const char* str, 
00319                                  std::vector<double> &values_f, 
00320                                  std::vector<double> &values_s);
00321 
00332     PCL_EXPORTS bool
00333     parse_multiple_3x_arguments (int argc, char** argv, const char* str, 
00334                                  std::vector<double> &values_f, 
00335                                  std::vector<double> &values_s, 
00336                                  std::vector<double> &values_t);
00337 
00344     PCL_EXPORTS std::vector<int>
00345     parse_file_extension_argument (int argc, char** argv, const std::string &ext);
00346   }
00347 }
00348 
00349 #endif      // PCL_CONSOLE_PARSE_H_
00350 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:33