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  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: parse.h 5155 2012-03-17 21:45:48Z rusu $
00037  *
00038  */
00039 #ifndef PCL_CONSOLE_PARSE_H_
00040 #define PCL_CONSOLE_PARSE_H_
00041 
00042 #include <vector>
00043 #include <string>
00044 #include <string.h>
00045 #include <stdlib.h>
00046 #include <boost/algorithm/string.hpp>
00047 #include <sstream>
00048 
00049 #include <pcl/pcl_macros.h>
00050 
00051 namespace pcl
00052 {
00053   namespace console
00054   {
00064     PCL_EXPORTS bool
00065     find_switch (int argc, char** argv, const char* argument_name);
00066 
00073     PCL_EXPORTS int
00074     find_argument (int argc, char** argv, const char* argument_name);
00075 
00083     template<typename Type> int
00084     parse (int argc, char** argv, const char* argument_name, Type& value)
00085     {
00086       int index = find_argument (argc, argv, argument_name) + 1;
00087 
00088       if (index > 0 && index < argc)
00089       {
00090         std::istringstream stream;
00091         stream.clear ();
00092         stream.str (argv[index]);
00093         stream >> value;
00094       }
00095 
00096       return (index - 1);
00097     }
00098 
00106     PCL_EXPORTS int
00107     parse_argument (int argc, char** argv, const char* str, std::string &val);
00108 
00116     PCL_EXPORTS int
00117     parse_argument (int argc, char** argv, const char* str, bool &val);
00118 
00126     PCL_EXPORTS int
00127     parse_argument (int argc, char** argv, const char* str, float &val);
00128     
00136     PCL_EXPORTS int
00137     parse_argument (int argc, char** argv, const char* str, double &val);
00138 
00146     PCL_EXPORTS int
00147     parse_argument (int argc, char** argv, const char* str, int &val);
00148 
00156     PCL_EXPORTS int
00157     parse_argument (int argc, char** argv, const char* str, unsigned int &val);
00158 
00166     PCL_EXPORTS int
00167     parse_argument (int argc, char** argv, const char* str, char &val);
00168 
00178     PCL_EXPORTS int
00179     parse_2x_arguments (int argc, char** argv, const char* str, float &f, float &s, bool debug = true);
00180 
00190     PCL_EXPORTS int
00191     parse_2x_arguments (int argc, char** argv, const char* str, double &f, double &s, bool debug = true);
00192 
00202     PCL_EXPORTS int
00203     parse_2x_arguments (int argc, char** argv, const char* str, int &f, int &s, bool debug = true);
00204 
00215     PCL_EXPORTS int
00216     parse_3x_arguments (int argc, char** argv, const char* str, float &f, float &s, float &t, bool debug = true);
00217 
00228     PCL_EXPORTS int
00229     parse_3x_arguments (int argc, char** argv, const char* str, double &f, double &s, double &t, bool debug = true);
00230 
00241     PCL_EXPORTS int
00242     parse_3x_arguments (int argc, char** argv, const char* str, int &f, int &s, int &t, bool debug = true);
00243 
00251     PCL_EXPORTS int
00252     parse_x_arguments (int argc, char** argv, const char* str, std::vector<double>& v);
00253 
00261     PCL_EXPORTS int
00262     parse_x_arguments (int argc, char** argv, const char* str, std::vector<float>& v);
00263 
00271     PCL_EXPORTS int
00272     parse_x_arguments (int argc, char** argv, const char* str, std::vector<int>& v);
00273 
00281     PCL_EXPORTS bool
00282     parse_multiple_arguments (int argc, char** argv, const char* str, std::vector<int> &values);
00283 
00291     PCL_EXPORTS bool
00292     parse_multiple_arguments (int argc, char** argv, const char* str, std::vector<float> &values);
00293 
00301     PCL_EXPORTS bool
00302     parse_multiple_arguments (int argc, char** argv, const char* str, std::vector<double> &values);
00303 
00311     PCL_EXPORTS bool
00312     parse_multiple_arguments (int argc, char** argv, const char* str, std::vector<std::string> &values);
00313 
00323     PCL_EXPORTS bool
00324     parse_multiple_2x_arguments (int argc, char** argv, const char* str, 
00325                                  std::vector<double> &values_f, 
00326                                  std::vector<double> &values_s);
00327 
00338     PCL_EXPORTS bool
00339     parse_multiple_3x_arguments (int argc, char** argv, const char* str, 
00340                                  std::vector<double> &values_f, 
00341                                  std::vector<double> &values_s, 
00342                                  std::vector<double> &values_t);
00343 
00350     PCL_EXPORTS std::vector<int>
00351     parse_file_extension_argument (int argc, char** argv, const std::string &ext);
00352   }
00353 }
00354 
00355 #endif      // PCL_CONSOLE_PARSE_H_
00356 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:15