conversion_impl.hpp
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 #ifndef VARIANT_IMPL_H
00036 #define VARIANT_IMPL_H
00037 
00038 #include <type_traits>
00039 #include <limits>
00040 #include <iostream>
00041 #include "ros_type_introspection/builtin_types.hpp"
00042 #include "ros_type_introspection/details/exceptions.hpp"
00043 
00044 namespace RosIntrospection
00045 {
00046 
00047 namespace details{
00048 
00049 template <typename T>
00050 using Invoke = typename T::type;
00051 
00052 
00053 template <typename BoolCondition>
00054 using EnableIf = Invoke<std::enable_if<BoolCondition::value> >;
00055 
00056 
00057 template <typename T>
00058 struct is_integer : std::integral_constant<bool, std::is_integral<T>::value
00059         && !std::is_same<T, bool>::value
00060         && !std::is_same<T, char>::value>
00061 {};
00062 
00063 template <typename From, typename To>
00064 struct is_same_real : std::integral_constant<bool,
00065     std::is_same<From, To>::value
00066     && std::is_floating_point<To>::value >
00067 {};
00068 
00069 
00070 template <typename From, typename To>
00071 struct is_safe_integer_conversion
00072         : std::integral_constant<bool, is_integer<From>::value
00073         && is_integer<To>::value
00074         && sizeof(From) <= sizeof(To)
00075         && std::is_signed<From>::value == std::is_signed<To>::value>
00076 {};
00077 
00078 template <typename From, typename To>
00079 struct float_conversion
00080         : std::integral_constant<bool, std::is_floating_point<From>::value
00081         && std::is_floating_point<To>::value 
00082         && !std::is_same<From,To>::value >
00083 {};
00084 
00085 template <typename From, typename To>
00086 struct unsigned_to_smaller_conversion
00087         : std::integral_constant<bool, is_integer<From>::value
00088         && is_integer<To>::value
00089         && (sizeof(From) > sizeof(To))
00090         && !std::is_signed<From>::value
00091         && !std::is_signed<To>::value >
00092 {};
00093 
00094 template <typename From, typename To>
00095 struct signed_to_smaller_conversion
00096         : std::integral_constant<bool, is_integer<From>::value
00097         && is_integer<To>::value
00098         && (sizeof(From) > sizeof(To))
00099 && std::is_signed<From>::value
00100 && std::is_signed<To>::value >
00101 {};
00102 
00103 //---------------------------
00104 template <typename From, typename To>
00105 struct signed_to_smaller_unsigned_conversion
00106         : std::integral_constant<bool, is_integer<From>::value
00107         && is_integer<To>::value
00108         && sizeof(From) >= sizeof(To)
00109         && std::is_signed<From>::value
00110         && !std::is_signed<To>::value >
00111 {};
00112 
00113 template <typename From, typename To>
00114 struct signed_to_larger_unsigned_conversion
00115         : std::integral_constant<bool, is_integer<From>::value
00116         && is_integer<To>::value
00117         && sizeof(From) < sizeof(To)
00118         && std::is_signed<From>::value
00119         && !std::is_signed<To>::value >
00120 {};
00121 
00122 template <typename From, typename To>
00123 struct unsigned_to_smaller_signed_conversion
00124         : std::integral_constant<bool, is_integer<From>::value
00125         && is_integer<To>::value
00126         && (sizeof(From) >= sizeof(To))
00127         && !std::is_signed<From>::value
00128         && std::is_signed<To>::value >
00129 {};
00130 
00131 template <typename From, typename To>
00132 struct unsigned_to_larger_signed_conversion
00133         : std::integral_constant<bool, is_integer<From>::value
00134         && is_integer<To>::value
00135         && sizeof(From) < sizeof(To)
00136         && !std::is_signed<From>::value
00137         && std::is_signed<To>::value >
00138 {};
00139 
00140 template <typename From, typename To>
00141 struct floating_to_signed_conversion
00142         : std::integral_constant<bool, std::is_floating_point<From>::value
00143         && is_integer<To>::value
00144         && std::is_signed<To>::value >
00145 {};
00146 
00147 template <typename From, typename To>
00148 struct floating_to_unsigned_conversion
00149         : std::integral_constant<bool, std::is_floating_point<From>::value
00150         && is_integer<To>::value
00151         && !std::is_signed<To>::value >
00152 {};
00153 
00154 template <typename From, typename To>
00155 struct integer_to_floating_conversion
00156         : std::integral_constant<bool, is_integer<From>::value
00157         && std::is_floating_point<To>::value >
00158 {};
00159 
00160 template <typename From, typename To>
00161 inline void checkUpperLimit(const From& from)
00162 {
00163     if ((sizeof(To) < sizeof(From)) &&
00164         (from > static_cast<From>(std::numeric_limits<To>::max()))) {
00165         throw RangeException("Value too large.");
00166     }
00167     else if (static_cast<To>(from) > std::numeric_limits<To>::max()) {
00168         throw RangeException("Value too large.");
00169     }
00170 }
00171 
00172 template <typename From, typename To>
00173 inline void checkUpperLimitFloat(const From& from)
00174 {
00175   if (from > std::numeric_limits<To>::max()){
00176     throw RangeException("Value too large.");
00177   }
00178 }
00179 
00180 template <typename From, typename To>
00181 inline void checkLowerLimitFloat(const From& from)
00182 {
00183     if (from < -std::numeric_limits<To>::max()){
00184         throw RangeException("Value too small.");
00185     }
00186 }
00187 
00188 template <typename From, typename To>
00189 inline void checkLowerLimit(const From& from)
00190 {
00191   if (from < std::numeric_limits<To>::min()){
00192     throw RangeException("Value too small.");
00193   }
00194 }
00195 
00196 template <typename From, typename To>
00197 inline void checkTruncation(const From& from)
00198 {
00199   if( from != static_cast<From>(static_cast<To>( from))){
00200     throw RangeException("Floating point truncated");
00201   }
00202 }
00203 
00204 
00205 //----------------------- Implementation ----------------------------------------------
00206 
00207 template<typename SRC,typename DST,
00208          typename details::EnableIf< details::is_same_real<SRC, DST>>* = nullptr >
00209 inline void convert_impl( const SRC& from, DST& target )
00210 {
00211     target = from;
00212 }
00213 
00214 
00215 template<typename SRC,typename DST,
00216          typename details::EnableIf< details::is_safe_integer_conversion<SRC, DST>>* = nullptr >
00217 inline void convert_impl( const SRC& from, DST& target )
00218 {
00219     //std::cout << "is_safe_integer_conversion" << std::endl;
00220     target = static_cast<DST>( from);
00221 }
00222 
00223 template<typename SRC,typename DST,
00224          typename details::EnableIf< details::float_conversion<SRC, DST>>* = nullptr >
00225 inline void convert_impl( const SRC& from, DST& target )
00226 {
00227     //std::cout << "float_conversion" << std::endl;
00228     checkTruncation<SRC,DST>(from);
00229     target = static_cast<DST>( from );
00230 }
00231 
00232 
00233 template<typename SRC,typename DST,
00234          typename details::EnableIf< details::unsigned_to_smaller_conversion<SRC, DST>>* = nullptr  >
00235 inline void convert_impl( const SRC& from, DST& target )
00236 {
00237     //std::cout << "unsigned_to_smaller_conversion" << std::endl;
00238 
00239     checkUpperLimit<SRC,DST>(from);
00240     target = static_cast<DST>( from);
00241 }
00242 
00243 template<typename SRC,typename DST,
00244          typename details::EnableIf< details::signed_to_smaller_conversion<SRC, DST>>* = nullptr  >
00245 inline void convert_impl( const SRC& from, DST& target )
00246 {
00247     //std::cout << "signed_to_smaller_conversion" << std::endl;
00248     checkLowerLimit<SRC,DST>(from);
00249     checkUpperLimit<SRC,DST>(from);
00250     target = static_cast<DST>( from);
00251 }
00252 
00253 
00254 template<typename SRC,typename DST,
00255          typename details::EnableIf< details::signed_to_smaller_unsigned_conversion<SRC, DST>>* = nullptr  >
00256 inline void convert_impl( const SRC& from, DST& target )
00257 {
00258     //std::cout << "signed_to_smaller_unsigned_conversion" << std::endl;
00259     if (from < 0 )
00260         throw RangeException("Value is negative and can't be converted to signed");
00261 
00262     checkUpperLimit<SRC,DST>(from);
00263 
00264     target = static_cast<DST>( from);
00265 }
00266 
00267 
00268 template<typename SRC,typename DST,
00269          typename details::EnableIf< details::signed_to_larger_unsigned_conversion<SRC, DST>>* = nullptr   >
00270 inline void convert_impl( const SRC& from, DST& target )
00271 {
00272     //std::cout << "signed_to_larger_unsigned_conversion" << std::endl;
00273 
00274     if ( from < 0 )
00275         throw RangeException("Value is negative and can't be converted to signed");
00276 
00277     target = static_cast<DST>( from);
00278 }
00279 
00280 template<typename SRC,typename DST,
00281          typename details::EnableIf< details::unsigned_to_larger_signed_conversion<SRC, DST>>* = nullptr   >
00282 inline void convert_impl( const SRC& from, DST& target )
00283 {
00284     //std::cout << "unsigned_to_larger_signed_conversion" << std::endl;
00285     target = static_cast<DST>( from);
00286 }
00287 
00288 template<typename SRC,typename DST,
00289          typename details::EnableIf< details::unsigned_to_smaller_signed_conversion<SRC, DST>>* = nullptr   >
00290 inline void convert_impl( const SRC& from, DST& target )
00291 {
00292     //std::cout << "unsigned_to_smaller_signed_conversion" << std::endl;
00293 
00294     checkUpperLimit<SRC,DST>(from);
00295     target = static_cast<DST>( from);
00296 }
00297 
00298 template<typename SRC,typename DST,
00299          typename details::EnableIf< details::floating_to_signed_conversion<SRC, DST>>* = nullptr   >
00300 inline void convert_impl( const SRC& from, DST& target )
00301 {
00302     //std::cout << "floating_to_signed_conversion" << std::endl;
00303 
00304     checkLowerLimitFloat<SRC,DST>(from);
00305     checkLowerLimitFloat<SRC,DST>(from);
00306 
00307     if( from != static_cast<SRC>(static_cast<DST>( from)))
00308         throw RangeException("Floating point truncated");
00309 
00310     target = static_cast<DST>( from);
00311 }
00312 
00313 template<typename SRC,typename DST,
00314          typename details::EnableIf< details::floating_to_unsigned_conversion<SRC, DST>>* = nullptr   >
00315 inline void convert_impl( const SRC& from, DST& target )
00316 {
00317     //std::cout << "floating_to_unsigned_conversion" << std::endl;
00318     if ( from < 0 )
00319         throw RangeException("Value is negative and can't be converted to signed");
00320 
00321     checkLowerLimitFloat<SRC,DST>(from);
00322 
00323     if( from != static_cast<SRC>(static_cast<DST>( from)))
00324         throw RangeException("Floating point truncated");
00325 
00326     target = static_cast<DST>( from);
00327 }
00328 
00329 template<typename SRC,typename DST,
00330          typename details::EnableIf< details::integer_to_floating_conversion<SRC, DST>>* = nullptr >
00331 inline void convert_impl( const SRC& from, DST& target )
00332 {
00333     //std::cout << "floating_to_unsigned_conversion" << std::endl;
00334 
00335     checkTruncation<SRC,DST>(from);
00336     target = static_cast<DST>( from);
00337 }
00338 
00339 } //end namespace details
00340 
00341 } //end namespace
00342 
00343 #endif // VARIANT_H
00344 


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