ros_time_type.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002 *                 This file is part of the OROCOS toolchain ROS project       *
00003 *                                                                             *
00004 *        (C) 2010 Steven Bellens, steven.bellens@mech.kuleuven.be             *
00005 *                    Department of Mechanical Engineering,                    *
00006 *                   Katholieke Universiteit Leuven, Belgium.                  *
00007 *                                                                             *
00008 *       You may redistribute this software and/or modify it under either the  *
00009 *       terms of the GNU Lesser General Public License version 2.1 (LGPLv2.1  *
00010 *       <http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html>) or (at your *
00011 *       discretion) of the Modified BSD License:                              *
00012 *       Redistribution and use in source and binary forms, with or without    *
00013 *       modification, are permitted provided that the following conditions    *
00014 *       are met:                                                              *
00015 *       1. Redistributions of source code must retain the above copyright     *
00016 *       notice, this list of conditions and the following disclaimer.         *
00017 *       2. Redistributions in binary form must reproduce the above copyright  *
00018 *       notice, this list of conditions and the following disclaimer in the   *
00019 *       documentation and/or other materials provided with the distribution.  *
00020 *       3. The name of the author may not be used to endorse or promote       *
00021 *       products derived from this software without specific prior written    *
00022 *       permission.                                                           *
00023 *       THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR  *
00024 *       IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED        *
00025 *       WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE    *
00026 *       ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT,*
00027 *       INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES    *
00028 *       (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS       *
00029 *       OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) *
00030 *       HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,   *
00031 *       STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING *
00032 *       IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE    *
00033 *       POSSIBILITY OF SUCH DAMAGE.                                           *
00034 *                                                                             *
00035 *******************************************************************************/
00036 
00037 #include "ros_primitives_typekit_plugin.hpp"
00038 
00039 namespace ros_integration{
00040     using namespace RTT;
00041     using namespace RTT::types;
00042 
00043     // This class works around the ROS time representation.
00044     class RosTimeTypeInfo : public types::PrimitiveTypeInfo<ros::Time,false>
00045     {
00046     public:
00047         RosTimeTypeInfo() : types::PrimitiveTypeInfo<ros::Time,false>("time") {}
00048 
00049         virtual std::ostream& write( std::ostream& os, base::DataSourceBase::shared_ptr in ) const {
00050             internal::DataSource<ros::Time>::shared_ptr d = boost::dynamic_pointer_cast< internal::DataSource<ros::Time> >( in );
00051             if ( d ) {
00052                 double tm = d->rvalue().sec + double(d->rvalue().nsec)/1000000000.0;
00053                 os << tm;
00054             } else {
00055                 std::string output = std::string("(")+ in->getTypeName() +")";
00056                 os << output;
00057             }
00058             return os;
00059         }
00060     };
00061 
00062     // This class works around the ROS time representation.
00063     class RosDurationTypeInfo : public types::PrimitiveTypeInfo<ros::Duration,false>
00064     {
00065     public:
00066         RosDurationTypeInfo() : types::PrimitiveTypeInfo<ros::Duration,false>("duration") {}
00067 
00068         virtual std::ostream& write( std::ostream& os, base::DataSourceBase::shared_ptr in ) const {
00069             internal::DataSource<ros::Duration>::shared_ptr d = boost::dynamic_pointer_cast< internal::DataSource<ros::Duration> >( in );
00070             if ( d ) {
00071                 double tm = d->rvalue().sec + double(d->rvalue().nsec)/1000000000.0;
00072                 os << tm;
00073             } else {
00074                 std::string output = std::string("(")+ in->getTypeName() +")";
00075                 os << output;
00076             }
00077             return os;
00078         }
00079     };
00080 
00081   void loadTimeTypes(){
00082              RTT::types::Types()->addType( new RosTimeTypeInfo );
00083              RTT::types::Types()->addType( new RosDurationTypeInfo );
00084   }
00085 }


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