ros_primitives_typekit_plugin.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002 *                 This file is part of the OROCOS toolchain ROS project       *
00003 *                                                                             *
00004 *        (C) 2010 Ruben Smits, ruben.smits@mech.kuleuven.be                   *
00005 *                 Steven Bellens, steven.bellens@mech.kuleuven.be             *
00006 *                    Department of Mechanical Engineering,                    *
00007 *                   Katholieke Universiteit Leuven, Belgium.                  *
00008 *                                                                             *
00009 *       You may redistribute this software and/or modify it under either the  *
00010 *       terms of the GNU Lesser General Public License version 2.1 (LGPLv2.1  *
00011 *       <http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html>) or (at your *
00012 *       discretion) of the Modified BSD License:                              *
00013 *       Redistribution and use in source and binary forms, with or without    *
00014 *       modification, are permitted provided that the following conditions    *
00015 *       are met:                                                              *
00016 *       1. Redistributions of source code must retain the above copyright     *
00017 *       notice, this list of conditions and the following disclaimer.         *
00018 *       2. Redistributions in binary form must reproduce the above copyright  *
00019 *       notice, this list of conditions and the following disclaimer in the   *
00020 *       documentation and/or other materials provided with the distribution.  *
00021 *       3. The name of the author may not be used to endorse or promote       *
00022 *       products derived from this software without specific prior written    *
00023 *       permission.                                                           *
00024 *       THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR  *
00025 *       IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED        *
00026 *       WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE    *
00027 *       ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT,*
00028 *       INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES    *
00029 *       (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS       *
00030 *       OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) *
00031 *       HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,   *
00032 *       STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING *
00033 *       IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE    *
00034 *       POSSIBILITY OF SUCH DAMAGE.                                           *
00035 *                                                                             *
00036 *******************************************************************************/
00037 
00038 #include "ros_primitives_typekit_plugin.hpp"
00039 
00040 namespace ros_integration {
00041 
00042     double float_to_double( float val ) {return double(val);}
00043     float double_to_float( double val ) {return float(val);}
00044     int32_t float_to_int(float f) { return int32_t(f); }
00045     float int_to_float(int i) { return float(i); }
00046     int32_t double_to_int(double f) { return int32_t(f); }
00047     double int_to_double(int32_t i) { return double(i); }
00048     uint32_t int_to_uint(int32_t i) { return (uint32_t)(i); }
00049     int uint_to_int(uint32_t ui) { return int32_t(ui); }
00050     bool int_to_bool(int32_t i) { return bool(i); }
00051 
00052     template<class T,class R>
00053     R a_to_b( T t ) { return R(t); }
00054 
00055     struct string_ctor
00056         : public std::unary_function<int, const std::string&>
00057     {
00058         mutable boost::shared_ptr< std::string > ptr;
00059         typedef const std::string& (Signature)( int );
00060         string_ctor()
00061             : ptr( new std::string() ) {}
00062         const std::string& operator()( int size ) const
00063         {
00064             ptr->resize( size );
00065             return *(ptr);
00066         }
00067     };
00068 
00069     void loadTimeTypes();
00070 
00071     void loadUInt8Types();
00072     void loadInt8Types();
00073 
00074     void loadUInt16Types();
00075     void loadInt16Types();
00076 
00077     void loadUInt32Types();
00078     void loadInt32Types();
00079 
00080     void loadUInt64Types();
00081     void loadInt64Types();
00082 
00083     void loadFloat32Types();
00084     void loadFloat64Types();
00085 
00086     void loadStringTypes();
00087 
00088     std::string ROSPrimitivesTypekitPlugin::getName(){
00089         return "ros-primitives";
00090     }
00091  
00092     bool ROSPrimitivesTypekitPlugin::loadTypes() {
00093       loadTimeTypes();
00094 
00095       loadInt8Types();
00096       loadUInt8Types();
00097 
00098       loadInt16Types();
00099       loadUInt16Types();
00100 
00101       loadInt32Types();
00102       loadUInt32Types();
00103 
00104       loadInt64Types();
00105       loadUInt64Types();
00106 
00107       loadFloat32Types();
00108       loadFloat64Types();
00109 
00110       loadStringTypes();
00111 
00112             return true;
00113     }
00114     bool ROSPrimitivesTypekitPlugin::loadOperators() { return true; }
00115     bool ROSPrimitivesTypekitPlugin::loadConstructors() { 
00116         types::TypeInfoRepository::shared_ptr ti = types::TypeInfoRepository::Instance();
00117         // x to float64
00118         ti->type("float64")->addConstructor( newConstructor( &float_to_double, true ));
00119         ti->type("float64")->addConstructor( newConstructor( &int_to_double, true ));
00120 
00121         // x to float
00122         ti->type("float")->addConstructor( newConstructor( &int_to_float, true ));
00123         ti->type("float")->addConstructor( newConstructor( &double_to_float, true ));
00124 
00125         // x to int
00126         ti->type("int32")->addConstructor( newConstructor( &float_to_int, false ));
00127         ti->type("int32")->addConstructor( newConstructor( &double_to_int, false ));
00128 
00129         // we certainly need int32/uint32 to 8/16 since the RTT parser only knows 32bit wide ints.
00130 
00131         // x to uint8_t (ROS' bool)
00132         ti->type("uint8")->addConstructor( newConstructor( &a_to_b<int8_t,uint8_t>, false ));
00133         ti->type("uint8")->addConstructor( newConstructor( &a_to_b<int16_t,uint8_t>, false ));
00134         ti->type("uint8")->addConstructor( newConstructor( &a_to_b<int32_t,uint8_t>, false ));
00135         ti->type("uint8")->addConstructor( newConstructor( &a_to_b<uint16_t,uint8_t>, false ));
00136         ti->type("uint8")->addConstructor( newConstructor( &a_to_b<uint32_t,uint8_t>, false ));
00137 
00138         ti->type("int8")->addConstructor( newConstructor( &a_to_b<uint8_t,int8_t>, false ));
00139         ti->type("int8")->addConstructor( newConstructor( &a_to_b<uint16_t,int8_t>, false ));
00140         ti->type("int8")->addConstructor( newConstructor( &a_to_b<uint32_t,int8_t>, false ));
00141         ti->type("int8")->addConstructor( newConstructor( &a_to_b<int16_t,int8_t>, false ));
00142         ti->type("int8")->addConstructor( newConstructor( &a_to_b<int32_t,int8_t>, false ));
00143 
00144         // x to uint16_t
00145         ti->type("uint16")->addConstructor( newConstructor( &a_to_b<int8_t,uint16_t>, false ));
00146         ti->type("uint16")->addConstructor( newConstructor( &a_to_b<int16_t,uint16_t>, false ));
00147         ti->type("uint16")->addConstructor( newConstructor( &a_to_b<int32_t,uint16_t>, false ));
00148         ti->type("uint16")->addConstructor( newConstructor( &a_to_b<uint8_t,uint16_t>, true ));
00149         ti->type("uint16")->addConstructor( newConstructor( &a_to_b<uint32_t,uint16_t>, false ));
00150 
00151         ti->type("int16")->addConstructor( newConstructor( &a_to_b<uint8_t,int16_t>, true ));
00152         ti->type("int16")->addConstructor( newConstructor( &a_to_b<uint16_t,int16_t>, false ));
00153         ti->type("int16")->addConstructor( newConstructor( &a_to_b<uint32_t,int16_t>, false ));
00154         ti->type("int16")->addConstructor( newConstructor( &a_to_b<int8_t,int16_t>, true ));
00155         ti->type("int16")->addConstructor( newConstructor( &a_to_b<int32_t,int16_t>, false ));
00156 
00157         // x to uint32_t
00158         ti->type("uint32")->addConstructor( newConstructor( &a_to_b<int8_t,uint32_t>, false ));
00159         ti->type("uint32")->addConstructor( newConstructor( &a_to_b<int16_t,uint32_t>, false ));
00160         ti->type("uint32")->addConstructor( newConstructor( &a_to_b<int32_t,uint32_t>, true ));
00161         ti->type("uint32")->addConstructor( newConstructor( &a_to_b<uint8_t,uint32_t>, true ));
00162         ti->type("uint32")->addConstructor( newConstructor( &a_to_b<uint16_t,uint32_t>, true ));
00163 
00164         ti->type("int32")->addConstructor( newConstructor( &a_to_b<uint8_t,int32_t>, true ));
00165         ti->type("int32")->addConstructor( newConstructor( &a_to_b<uint16_t,int32_t>, true ));
00166         ti->type("int32")->addConstructor( newConstructor( &a_to_b<uint32_t,int32_t>, true ));
00167         ti->type("int32")->addConstructor( newConstructor( &a_to_b<int8_t,int32_t>, true ));
00168         ti->type("int32")->addConstructor( newConstructor( &a_to_b<int16_t,int32_t>, true ));
00169 
00170         ti->type("string")->addConstructor( newConstructor( string_ctor() ) );
00171         ti->type("duration")->addConstructor( newConstructor ( &a_to_b<double,ros::Duration>, true));
00172         ti->type("time")->addConstructor( newConstructor ( &a_to_b<double,ros::Time>, true));
00173         return true; 
00174     }
00175 };
00176 
00177 ORO_TYPEKIT_PLUGIN( ros_integration::ROSPrimitivesTypekitPlugin )
00178 


rtt_ros
Author(s): Ruben Smits
autogenerated on Mon Apr 3 2017 03:34:15