parser.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright 2016 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 ROSTypePARSER_H
00036 #define ROSTypePARSER_H
00037 
00038 #include <vector>
00039 #include <map>
00040 #include <boost/function.hpp>
00041 #include <boost/utility/string_ref.hpp>
00042 #include "ros_type_introspection/stringtree.hpp"
00043 #include "ros_type_introspection/variant.hpp"
00044 
00045 namespace RosIntrospection{
00046 
00047 
00048 #if 1
00049 // Faster, but might need more testing
00050 typedef ssoX::basic_string<char> SString;
00051 #else
00052 // slightly slower but safer option. More convenient during debug
00053 typedef std::string SString;
00054 #endif
00055 
00056 typedef details::TreeElement<SString> StringTreeNode;
00057 typedef details::Tree<SString> StringTree;
00058 
00062 class ROSType {
00063 public:
00064 
00065   ROSType(){}
00066 
00067   ROSType(const std::string& name);
00068 
00071   const SString& baseName() const;
00072 
00074   const SString& msgName()  const;
00075 
00077   const SString& pkgName()  const;
00078 
00079   void setPkgName(const SString& new_pkg);
00080 
00082   bool isArray() const;
00083 
00085   bool isBuiltin() const;
00086 
00089   int  arraySize() const;
00090 
00092   int typeSize() const;
00093 
00095   BuiltinType typeID() const;
00096 
00097   bool operator==(const ROSType& other) const  {
00098     return this->baseName() == other.baseName();
00099   }
00100 
00101   bool operator<(const ROSType& other) const {
00102     return this->baseName() < other.baseName();
00103   }
00104 
00105   VarNumber deserializeFromBuffer(uint8_t** buffer) const
00106   {
00107       if(!_deserialize_impl){ return VarNumber(); }
00108       else{
00109           return _deserialize_impl(buffer);
00110       }
00111   }
00112 
00113 protected:
00114 
00115   BuiltinType _id;
00116   int     _array_size;
00117   SString _base_name;
00118   SString _msg_name;
00119   SString _pkg_name;
00120   boost::function<VarNumber(uint8_t** buffer)> _deserialize_impl;
00121 
00122 };
00123 
00124 // helper function to deserialize raw memory
00125 template <typename T> inline T ReadFromBuffer( uint8_t** buffer)
00126 {
00127   T destination =  (*( reinterpret_cast<T*>( *buffer ) ) );
00128   *buffer +=  sizeof(T);
00129   return (destination);
00130 }
00131 
00132 
00137 class ROSField {
00138 public:
00139   ROSField(const std::string& name, const ROSType& type ):
00140     _name( name ), _type( type ) {}
00141 
00142   ROSField(const std::string& definition );
00143 
00144   const SString&  name() const { return _name; }
00145 
00146   const ROSType&  type() const { return _type; }
00147 
00149   bool isConstant() const {
00150     return _value.size() != 0;
00151   }
00152 
00154   const SString& value() const   { return _value; }
00155 
00156   friend class ROSMessage;
00157 
00158 protected:
00159   SString _name;
00160   ROSType _type;
00161   SString _value;
00162 };
00163 
00164 class ROSMessage;
00165 typedef std::vector<ROSMessage> ROSTypeList;
00166 
00167 
00168 
00169 class ROSMessage{
00170 public:
00171 
00174   ROSMessage(const std::string& msg_def );
00175 
00182   void updateTypes(const std::vector<ROSType> &all_types);
00183 
00188   const ROSField* field(const SString& name) const;
00189 
00193   const ROSField& field(size_t index) const { return _fields[index]; }
00194 
00199   const std::vector<ROSField>& fields() const { return _fields; }
00200 
00201   const ROSType& type() const { return _type; }
00202 
00203   void mutateType(const ROSType& new_type ) { _type = new_type; }
00204 
00205 private:
00206   ROSType _type;
00207   std::vector<ROSField> _fields;
00208 };
00209 
00210 
00211 inline const ROSField* ROSMessage::field(const SString &name) const
00212 {
00213   for(int i=0; i<_fields.size(); i++ )  {
00214     if(  name ==_fields[i].name() ) {
00215       return &_fields[i];
00216     }
00217   }
00218   return nullptr;
00219 }
00220 
00221 
00222 //------------------------------
00223 
00239 ROSTypeList buildROSTypeMapFromDefinition(
00240     const std::string& type_name,
00241     const std::string& msg_definition);
00242 
00243 std::ostream& operator<<(std::ostream& s, const ROSTypeList& c);
00244 
00245 
00246 } // end namespace
00247 
00248 #endif // ROSTypePARSER_H


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Sun Oct 1 2017 02:54:53