exceptions.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-2011, 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  */
00037 #ifndef PCL_EXCEPTIONS_H_
00038 #define PCL_EXCEPTIONS_H_
00039 
00040 #include <stdexcept>
00041 #include <sstream>
00042 #include <pcl/pcl_macros.h>
00043 
00044 namespace pcl
00045 {
00046 
00051   class PCLException : public std::runtime_error
00052   {
00053     public:
00054 
00055       PCLException (const std::string& error_description,
00056                     const std::string& file_name = "",
00057                     const std::string& function_name = "" ,
00058                     unsigned line_number = 0) throw ()
00059       : std::runtime_error (error_description)
00060       , file_name_ (file_name)
00061       , function_name_ (function_name)
00062       , line_number_ (line_number)
00063       {}
00064       
00065       virtual ~PCLException () throw ()
00066       {}
00067       
00068       const std::string&
00069       getFileName () const throw ()
00070       {
00071         return file_name_;
00072       }
00073 
00074       const std::string&
00075       getFunctionName () const throw ()
00076       {
00077         return function_name_;
00078       }
00079 
00080       unsigned
00081       getLineNumber () const throw ()
00082       {
00083         return line_number_;
00084       }
00085 
00086       std::string 
00087       detailedMessage () const throw ()
00088       {
00089         std::stringstream sstream;
00090         if (function_name_ != "")
00091           sstream << function_name_ << " ";
00092         
00093         if (file_name_ != "")
00094         {
00095           sstream << "in " << file_name_ << " ";
00096           if (line_number_ != 0)
00097             sstream << "@ " << line_number_ << " ";
00098         }
00099         sstream << ":" << what ();
00100         
00101         return sstream.str ();
00102       }
00103 
00104     protected:
00105       std::string file_name_;
00106       std::string function_name_;
00107       unsigned line_number_;
00108   } ;
00109 
00113   class InvalidConversionException : public PCLException
00114   {
00115     public:
00116 
00117       InvalidConversionException (const std::string& error_description,
00118                                   const std::string& file_name = "",
00119                                   const std::string& function_name = "" ,
00120                                   unsigned line_number = 0) throw ()
00121         : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00122   } ;
00123 
00127   class IsNotDenseException : public PCLException
00128   {
00129     public:
00130 
00131       IsNotDenseException (const std::string& error_description,
00132                            const std::string& file_name = "",
00133                            const std::string& function_name = "" ,
00134                            unsigned line_number = 0) throw ()
00135         : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00136   } ;
00137 
00142   class InvalidSACModelTypeException : public PCLException
00143   {
00144     public:
00145 
00146       InvalidSACModelTypeException (const std::string& error_description,
00147                                     const std::string& file_name = "",
00148                                     const std::string& function_name = "" ,
00149                                     unsigned line_number = 0) throw ()
00150         : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00151   } ;
00152 
00156   class IOException : public PCLException
00157   {
00158     public:
00159 
00160       IOException (const std::string& error_description,
00161                    const std::string& file_name = "",
00162                    const std::string& function_name = "" ,
00163                    unsigned line_number = 0) throw ()
00164         : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00165   } ;
00166 
00171   class InitFailedException : public PCLException
00172   {
00173     public:
00174       InitFailedException (const std::string& error_description = "",
00175                            const std::string& file_name = "",
00176                            const std::string& function_name = "" ,
00177                            unsigned line_number = 0) throw ()
00178         : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00179   } ;
00180 
00185   class UnorganizedPointCloudException : public PCLException
00186   {
00187     public:
00188     
00189       UnorganizedPointCloudException (const std::string& error_description,
00190                                       const std::string& file_name = "",
00191                                       const std::string& function_name = "" ,
00192                                       unsigned line_number = 0) throw ()
00193         : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00194   } ;
00195 
00199   class KernelWidthTooSmallException : public PCLException
00200   {
00201     public:
00202     
00203     KernelWidthTooSmallException (const std::string& error_description,
00204                                   const std::string& file_name = "",
00205                                   const std::string& function_name = "" ,
00206                                   unsigned line_number = 0) throw ()
00207       : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00208   } ;
00209 
00210   class UnhandledPointTypeException : public PCLException
00211   {
00212     public:
00213     UnhandledPointTypeException (const std::string& error_description,
00214                                  const std::string& file_name = "",
00215                                  const std::string& function_name = "" ,
00216                                  unsigned line_number = 0) throw ()
00217       : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00218   };
00219 
00220   class ComputeFailedException : public PCLException
00221   {
00222     public:
00223     ComputeFailedException (const std::string& error_description,
00224                             const std::string& file_name = "",
00225                             const std::string& function_name = "" ,
00226                             unsigned line_number = 0) throw ()
00227       : pcl::PCLException (error_description, file_name, function_name, line_number) { }
00228   };
00229 
00230 }
00231 
00237 #define PCL_THROW_EXCEPTION(ExceptionName, message)         \
00238 {                                                           \
00239   std::ostringstream s;                                     \
00240   s << message;                                             \
00241   throw ExceptionName(s.str(), __FILE__, "", __LINE__);     \
00242 }
00243 
00244 #endif


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:54