type.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef CPP_INTROSPECTION_TYPE_H
00030 #define CPP_INTROSPECTION_TYPE_H
00031 
00032 #include <introspection/forwards.h>
00033 
00034 #include <boost/any.hpp>
00035 #include <boost/enable_shared_from_this.hpp>
00036 #include <boost/lexical_cast.hpp>
00037 
00038 #include <ros/time.h>
00039 #include <ros/console.h>
00040 #include <std_msgs/String.h>
00041 #include <std_msgs/Bool.h>
00042 
00043 #define CATCH_BAD_CAST_EXCEPTION_AND_RETURN(return_value, default_value) \
00044   try { \
00045     return return_value; \
00046   } catch (boost::bad_any_cast&) { \
00047     ROS_WARN_NAMED("cpp_introspection", "bad_any_cast exception while trying to convert a value of type %s", getName()); \
00048     return default_value; \
00049   } catch (boost::bad_lexical_cast&) { \
00050     return default_value; \
00051   } while(0)
00052 
00053 
00054 namespace cpp_introspection {
00055 
00056   class Type : public boost::enable_shared_from_this<Type>
00057   {
00058   private:
00059     const char *name_;
00060 
00061   public:
00062     Type(const char *name) : name_(name) {}
00063     virtual ~Type() {}
00064     static const TypePtr& add(const TypePtr& type, const std::string& alias = std::string());
00065 
00066     virtual const char *getName() const { return name_; }
00067     virtual const std::type_info& getTypeId() const = 0;
00068     virtual bool isNumeric() const { return false; }
00069     virtual bool isString() const { return false; }
00070 
00071     template <typename T> bool is() const { return &(getTypeId()) && (getTypeId() == typeid(T)); }
00072     template <typename TargetType> TargetType as(const boost::any& value) const;
00073     template <typename SourceType> boost::any from(const SourceType& value) const;
00074 
00075     virtual std::string as_string(const boost::any& value) const = 0;
00076     virtual double      as_double(const boost::any& value) const = 0;
00077     virtual int         as_int(const boost::any& value) const = 0;
00078     virtual unsigned    as_unsigned(const boost::any& value) const = 0;
00079     virtual boost::any  from_string(const std::string& value) const = 0;
00080     virtual boost::any  from_double(double value) const = 0;
00081     virtual boost::any  from_int(int value) const = 0;
00082     virtual boost::any  from_unsigned(unsigned value) const = 0;
00083 
00084     struct StaticInitializer { StaticInitializer(const TypePtr& type); };
00085     TypePtr alias(const std::string& name) const;
00086 
00087     bool operator==(const Type& other) { return &getTypeId() && &other.getTypeId() && getTypeId() == other.getTypeId(); }
00088   };
00089 
00090   struct UnknownType : public Type
00091   {
00092   public:
00093     UnknownType() : Type("(unknown)") {}
00094     virtual ~UnknownType() {}
00095     static TypePtr Instance();
00096 
00097     virtual const std::type_info& getTypeId() const { return *static_cast<const std::type_info *>(0); }
00098 
00099     virtual std::string as_string(const boost::any& value) const    { return std::string(); }
00100     virtual double      as_double(const boost::any& value) const    { return std::numeric_limits<double>::quiet_NaN(); }
00101     virtual int         as_int(const boost::any& value) const       { return 0; }
00102     virtual unsigned    as_unsigned(const boost::any& value) const  { return 0; }
00103     virtual boost::any  from_string(const std::string& value) const { return boost::any(); }
00104     virtual boost::any  from_double(double value) const             { return boost::any(); }
00105     virtual boost::any  from_int(int value) const                   { return boost::any(); }
00106     virtual boost::any  from_unsigned(unsigned value) const         { return boost::any(); }
00107   };
00108 
00109   template <typename T>
00110   class NumericType : public Type
00111   {
00112   public:
00113     typedef T type;
00114 
00115     NumericType(const char *name) : Type(name) {}
00116     virtual ~NumericType() {}
00117 
00118     virtual const std::type_info& getTypeId() const { return typeid(type); }
00119     virtual bool isNumeric() const { return true; }
00120 
00121     virtual std::string as_string(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(boost::lexical_cast<std::string>(boost::any_cast<type>(value)), std::string()); }
00122     virtual double      as_double(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(double(boost::any_cast<type>(value)), std::numeric_limits<double>::quiet_NaN()); }
00123     virtual int         as_int(const boost::any& value) const       { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(int(boost::any_cast<type>(value)), 0); }
00124     virtual unsigned    as_unsigned(const boost::any& value) const  { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(unsigned(boost::any_cast<type>(value)), 0); }
00125     virtual boost::any  from_string(const std::string& value) const { return boost::any(boost::lexical_cast<type>(value)); }
00126     virtual boost::any  from_double(double value) const             { return boost::any(type(value)); }
00127     virtual boost::any  from_int(int value) const                   { return boost::any(type(value)); }
00128     virtual boost::any  from_unsigned(unsigned value) const         { return boost::any(type(value)); }
00129   };
00130 
00131   class BoolType : public Type
00132   {
00133   public:
00134     typedef std_msgs::Bool::_data_type type;
00135 
00136     BoolType(const char *name) : Type(name) {}
00137     virtual ~BoolType() {}
00138 
00139     virtual const std::type_info& getTypeId() const { return typeid(type); }
00140     virtual bool isNumeric() const { return true; }
00141 
00142     virtual std::string as_string(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(boost::lexical_cast<std::string>(boost::any_cast<type>(value)), std::string()); }
00143     virtual double      as_double(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(double(boost::any_cast<type>(value)), std::numeric_limits<double>::quiet_NaN()); }
00144     virtual int         as_int(const boost::any& value) const       { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(int(boost::any_cast<type>(value)), 0); }
00145     virtual unsigned    as_unsigned(const boost::any& value) const  { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(unsigned(boost::any_cast<type>(value)), 0); }
00146     virtual boost::any  from_string(const std::string& value) const { return boost::any(type(boost::lexical_cast<bool>(value))); }
00147     virtual boost::any  from_double(double value) const             { return boost::any(type(value)); }
00148     virtual boost::any  from_int(int value) const                   { return boost::any(type(value)); }
00149     virtual boost::any  from_unsigned(unsigned value) const         { return boost::any(type(value)); }
00150   };
00151 
00152   class StringType : public Type
00153   {
00154   public:
00155     typedef std_msgs::String::_data_type type;
00156 
00157     StringType(const char *name) : Type(name) {}
00158     virtual ~StringType() {}
00159 
00160     virtual const std::type_info& getTypeId() const { return typeid(type); }
00161     virtual bool isString() const { return true; }
00162 
00163     virtual std::string as_string(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(boost::any_cast<type>(value), std::string()); }
00164     virtual double      as_double(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(boost::lexical_cast<double>(boost::any_cast<type>(value)), std::numeric_limits<double>::quiet_NaN()); }
00165     virtual int         as_int(const boost::any& value) const       { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(boost::lexical_cast<int>(boost::any_cast<type>(value)), 0); }
00166     virtual unsigned    as_unsigned(const boost::any& value) const  { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(boost::lexical_cast<unsigned>(boost::any_cast<type>(value)), 0); }
00167     virtual boost::any  from_string(const std::string& value) const { return boost::any(type(value)); }
00168     virtual boost::any  from_double(double value) const             { return boost::any(boost::lexical_cast<type>(value)); }
00169     virtual boost::any  from_int(int value) const                   { return boost::any(boost::lexical_cast<type>(value)); }
00170     virtual boost::any  from_unsigned(unsigned value) const         { return boost::any(boost::lexical_cast<type>(value)); }
00171   };
00172 
00173   class TimeType : public Type
00174   {
00175   public:
00176     typedef ros::Time type;
00177 
00178     TimeType(const char *name) : Type(name) {}
00179     virtual ~TimeType() {}
00180 
00181     virtual const std::type_info& getTypeId() const { return typeid(type); }
00182     virtual bool isNumeric() const { return true; }
00183 
00184     virtual std::string as_string(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(boost::lexical_cast<std::string>(boost::any_cast<type>(value).toSec()), std::string()); }
00185     virtual double      as_double(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(double(boost::any_cast<type>(value).toSec()), std::numeric_limits<double>::quiet_NaN()); }
00186     virtual int         as_int(const boost::any& value) const       { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(int(boost::any_cast<type>(value).toSec()), 0); }
00187     virtual unsigned    as_unsigned(const boost::any& value) const  { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(unsigned(boost::any_cast<type>(value).toSec()), 0); }
00188     virtual boost::any  from_string(const std::string& value) const { return boost::any(type(boost::lexical_cast<double>(value))); }
00189     virtual boost::any  from_double(double value) const             { return boost::any(type(value)); }
00190     virtual boost::any  from_int(int value) const                   { return boost::any(type(double(value))); }
00191     virtual boost::any  from_unsigned(unsigned value) const         { return boost::any(type(double(value))); }
00192   };
00193 
00194   class DurationType : public Type
00195   {
00196   public:
00197     typedef ros::Duration type;
00198 
00199     DurationType(const char *name) : Type(name) {}
00200     virtual ~DurationType() {}
00201 
00202     virtual const std::type_info& getTypeId() const { return typeid(type); }
00203     virtual bool isNumeric() const { return true; }
00204 
00205     virtual std::string as_string(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(boost::lexical_cast<std::string>(boost::any_cast<type>(value).toSec()), std::string()); }
00206     virtual double      as_double(const boost::any& value) const    { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(double(boost::any_cast<type>(value).toSec()), std::numeric_limits<double>::quiet_NaN()); }
00207     virtual int         as_int(const boost::any& value) const       { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(int(boost::any_cast<type>(value).toSec()), 0); }
00208     virtual unsigned    as_unsigned(const boost::any& value) const  { CATCH_BAD_CAST_EXCEPTION_AND_RETURN(unsigned(boost::any_cast<type>(value).toSec()), 0); }
00209     virtual boost::any  from_string(const std::string& value) const { return boost::any(type(boost::lexical_cast<double>(value))); }
00210     virtual boost::any  from_double(double value) const             { return boost::any(type(value)); }
00211     virtual boost::any  from_int(int value) const                   { return boost::any(type(double(value))); }
00212     virtual boost::any  from_unsigned(unsigned value) const         { return boost::any(type(double(value))); }
00213   };
00214 
00215   TypePtr type(const std::string& name);
00216 
00217 } // namespace cpp_introspection
00218 
00219 #include <introspection/conversion.h>
00220 
00221 #endif // CPP_INTROSPECTION_TYPE_H


cpp_introspection
Author(s): Johannes Meyer
autogenerated on Sat Jun 8 2019 19:46:00