general.h
Go to the documentation of this file.
00001 /***********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright 2008-2009  Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
00005  * Copyright 2008-2009  David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
00006  *
00007  * THE BSD LICENSE
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  * 1. Redistributions of source code must retain the above copyright
00014  *    notice, this list of conditions and the following disclaimer.
00015  * 2. Redistributions in binary form must reproduce the above copyright
00016  *    notice, this list of conditions and the following disclaimer in the
00017  *    documentation and/or other materials provided with the distribution.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
00020  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
00021  * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
00022  * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
00023  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
00024  * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00025  * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
00026  * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00028  * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029  *************************************************************************/
00030 
00031 #ifndef RTABMAP_FLANN_GENERAL_H_
00032 #define RTABMAP_FLANN_GENERAL_H_
00033 
00034 #include "defines.h"
00035 #include <stdexcept>
00036 #include <cassert>
00037 #include <limits.h>
00038 
00039 namespace rtflann
00040 {
00041 
00042 class FLANNException : public std::runtime_error
00043 {
00044 public:
00045     FLANNException(const char* message) : std::runtime_error(message) { }
00046 
00047     FLANNException(const std::string& message) : std::runtime_error(message) { }
00048 };
00049 
00050 
00051 template <typename T>
00052 struct flann_datatype_value
00053 {
00054         static const flann_datatype_t value = FLANN_NONE;
00055 };
00056 
00057 template<>
00058 struct flann_datatype_value<char>
00059 {
00060         static const flann_datatype_t value = FLANN_INT8;
00061 };
00062 
00063 template<>
00064 struct flann_datatype_value<short>
00065 {
00066         static const flann_datatype_t value = FLANN_INT16;
00067 };
00068 
00069 template<>
00070 struct flann_datatype_value<int>
00071 {
00072         static const flann_datatype_t value = FLANN_INT32;
00073 };
00074 
00075 #ifdef LLONG_MAX
00076 template<>
00077 struct flann_datatype_value<long long>
00078 {
00079         static const flann_datatype_t value = FLANN_INT64;
00080 };
00081 #endif
00082 
00083 template<>
00084 struct flann_datatype_value<unsigned char>
00085 {
00086         static const flann_datatype_t value = FLANN_UINT8;
00087 };
00088 
00089 template<>
00090 struct flann_datatype_value<unsigned short>
00091 {
00092         static const flann_datatype_t value = FLANN_UINT16;
00093 };
00094 
00095 template<>
00096 struct flann_datatype_value<unsigned int>
00097 {
00098         static const flann_datatype_t value = FLANN_UINT32;
00099 };
00100 
00101 #ifdef ULLONG_MAX
00102 template<>
00103 struct flann_datatype_value<unsigned long long>
00104 {
00105         static const flann_datatype_t value = FLANN_UINT64;
00106 };
00107 #endif
00108 
00109 
00110 template<>
00111 struct flann_datatype_value<float>
00112 {
00113         static const flann_datatype_t value = FLANN_FLOAT32;
00114 };
00115 
00116 template<>
00117 struct flann_datatype_value<double>
00118 {
00119         static const flann_datatype_t value = FLANN_FLOAT64;
00120 };
00121 
00122 
00123 
00124 template <flann_datatype_t datatype>
00125 struct flann_datatype_type
00126 {
00127         typedef void type;
00128 };
00129 
00130 template<>
00131 struct flann_datatype_type<FLANN_INT8>
00132 {
00133         typedef char type;
00134 };
00135 
00136 template<>
00137 struct flann_datatype_type<FLANN_INT16>
00138 {
00139         typedef short type;
00140 };
00141 
00142 template<>
00143 struct flann_datatype_type<FLANN_INT32>
00144 {
00145         typedef int type;
00146 };
00147 
00148 #ifdef LLONG_MAX
00149 template<>
00150 struct flann_datatype_type<FLANN_INT64>
00151 {
00152         typedef long long type;
00153 };
00154 #endif
00155 
00156 template<>
00157 struct flann_datatype_type<FLANN_UINT8>
00158 {
00159         typedef unsigned char type;
00160 };
00161 
00162 
00163 template<>
00164 struct flann_datatype_type<FLANN_UINT16>
00165 {
00166         typedef unsigned short type;
00167 };
00168 
00169 template<>
00170 struct flann_datatype_type<FLANN_UINT32>
00171 {
00172         typedef unsigned int type;
00173 };
00174 
00175 #ifdef ULLONG_MAX
00176 template<>
00177 struct flann_datatype_type<FLANN_UINT64>
00178 {
00179         typedef unsigned long long type;
00180 };
00181 #endif
00182 
00183 template<>
00184 struct flann_datatype_type<FLANN_FLOAT32>
00185 {
00186         typedef float type;
00187 };
00188 
00189 template<>
00190 struct flann_datatype_type<FLANN_FLOAT64>
00191 {
00192         typedef double type;
00193 };
00194 
00195 
00196 inline size_t flann_datatype_size(flann_datatype_t type)
00197 {
00198         switch (type) {
00199         case FLANN_INT8:
00200                 return sizeof(flann_datatype_type<FLANN_INT8>::type);
00201         case FLANN_INT16:
00202                 return sizeof(flann_datatype_type<FLANN_INT16>::type);
00203         case FLANN_INT32:
00204                 return sizeof(flann_datatype_type<FLANN_INT32>::type);
00205         case FLANN_INT64:
00206                 return sizeof(flann_datatype_type<FLANN_INT64>::type);
00207         case FLANN_UINT8:
00208                 return sizeof(flann_datatype_type<FLANN_UINT8>::type);
00209         case FLANN_UINT16:
00210                 return sizeof(flann_datatype_type<FLANN_UINT16>::type);
00211         case FLANN_UINT32:
00212                 return sizeof(flann_datatype_type<FLANN_UINT32>::type);
00213         case FLANN_UINT64:
00214                 return sizeof(flann_datatype_type<FLANN_UINT64>::type);
00215         case FLANN_FLOAT32:
00216                 return sizeof(flann_datatype_type<FLANN_FLOAT32>::type);
00217         case FLANN_FLOAT64:
00218                 return sizeof(flann_datatype_type<FLANN_FLOAT64>::type);
00219         default:
00220                 return 0;
00221         }
00222 }
00223 
00224 }
00225 
00226 
00227 #endif  /* RTABMAP_FLANN_GENERAL_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:16