ros_type.cpp
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 
00036 #include "ros_type_introspection/ros_type.hpp"
00037 #include "ros_type_introspection/helper_functions.hpp"
00038 #include <absl/strings/substitute.h>
00039 
00040 namespace RosIntrospection{
00041 
00042 ROSType::ROSType(absl::string_view name):
00043   _base_name(name)
00044 {
00045   int pos = -1;
00046   for (size_t i=0; i<name.size(); i++)
00047   {
00048     if(name[i] == '/'){
00049       pos = i;
00050       break;
00051     }
00052   }
00053 
00054   if( pos == -1)
00055   {
00056     _msg_name = _base_name;
00057   }
00058   else{
00059     _pkg_name = absl::string_view( _base_name.data(), pos);
00060     pos++;
00061     _msg_name = absl::string_view( _base_name.data() + pos, _base_name.size() - pos);
00062   }
00063 
00064   _id   = toBuiltinType( _msg_name );
00065   _hash = std::hash<std::string>{}( _base_name );
00066 }
00067 
00068 ROSType& ROSType::operator= (const ROSType &other)
00069 {
00070     int pos = other._pkg_name.size();
00071     _base_name = other._base_name;
00072     _pkg_name = absl::string_view( _base_name.data(), pos);
00073     if( pos > 0) pos++;
00074     _msg_name = absl::string_view( _base_name.data() + pos, _base_name.size() - pos);
00075     _id   = other._id;
00076     _hash = other._hash;
00077     return *this;
00078 }
00079 
00080 ROSType& ROSType::operator= (ROSType &&other)
00081 {
00082     int pos = other._pkg_name.size();
00083     _base_name = std::move( other._base_name );
00084     _pkg_name = absl::string_view( _base_name.data(), pos);
00085     if( pos > 0) pos++;
00086     _msg_name = absl::string_view( _base_name.data() + pos, _base_name.size() - pos);
00087     _id   = other._id;
00088     _hash = other._hash;
00089     return *this;
00090 }
00091 
00092 
00093 void ROSType::setPkgName(absl::string_view new_pkg)
00094 {
00095   assert(_pkg_name.size() == 0);
00096 
00097   int pos = new_pkg.size();
00098   _base_name = absl::Substitute("$0/$1", new_pkg, _base_name);
00099 
00100   _pkg_name = absl::string_view( _base_name.data(), pos++);
00101   _msg_name = absl::string_view( _base_name.data() + pos, _base_name.size() - pos);
00102 
00103   _hash = std::hash<std::string>{}( _base_name );
00104 }
00105 
00106 
00107 }


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