TimeService.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002  tag: Peter Soetens  Wed Apr 17 16:01:31 CEST 2002  TimeService.cpp
00003 
00004                        TimeService.cpp -  description
00005                           -------------------
00006    begin                : Wed April 17 2002
00007    copyright            : (C) 2002 Peter Soetens
00008    email                : peter.soetens@mech.kuleuven.ac.be
00009 
00010 ***************************************************************************
00011 *                                                                         *
00012 *   This program is free software; you can redistribute it and/or modify  *
00013 *   it under the terms of the GNU General Public License as published by  *
00014 *   the Free Software Foundation; either version 2 of the License, or     *
00015 *   (at your option) any later version.                                   *
00016 *                                                                         *
00017 ***************************************************************************/
00018 
00019 #include "os/fosi.h"
00020 #include "TimeService.hpp"
00021 
00022 namespace RTT {
00023     using namespace os;
00024 
00025     TimeService* TimeService::_instance = 0;
00026 
00027     const TimeService::ticks TimeService::InfiniteTicks = ::InfiniteTicks;
00028     const TimeService::nsecs TimeService::InfiniteNSecs = ::InfiniteNSecs;
00029     const TimeService::Seconds TimeService::InfiniteSeconds  = ::InfiniteSeconds;
00030 
00031     TimeService::ticks TimeService::nsecs2ticks( const nsecs m )
00032     {
00033         return nano2ticks( m );
00034     }
00035 
00036     TimeService::nsecs TimeService::ticks2nsecs( const ticks t )
00037     {
00038         return ticks2nano( t );
00039     }
00040 
00041     TimeService* TimeService::Instance()
00042     {
00043         if ( _instance == 0 )
00044         {
00045             _instance = new TimeService();
00046         }
00047 
00048         return _instance;
00049     }
00050 
00051 
00052     bool TimeService::Release()
00053     {
00054         if ( _instance != 0 )
00055         {
00056             delete _instance;
00057             _instance = 0;
00058             return true;
00059         }
00060 
00061         return false;
00062     }
00063 
00064 
00065     TimeService::TimeService()
00066         : offset(0), use_clock(true)
00067     {
00068         //os::cout << "HeartBeat Created\n";
00069     }
00070 
00071     TimeService::~TimeService()
00072     {
00073         //os::cout << "HB DESTRUCTOR\n";
00074     }
00075 
00076     void TimeService::enableSystemClock( bool yes_no )
00077     {
00078         // guarantee monotonous time increase :
00079         if ( yes_no == use_clock )
00080             return;
00081         // we switched from one time domain to the other
00082         use_clock=yes_no;
00083         if ( use_clock == true )
00084             {
00085                 // if offset is X, then start counting from X.
00086                 offset = offset - rtos_get_time_ticks();
00087             }
00088         else
00089             {
00090                 // start counting from _now_ + old offset
00091                 offset = offset + rtos_get_time_ticks();
00092             }
00093     }
00094 
00095 
00096     TimeService::ticks
00097     TimeService::getTicks() const
00098     {
00099         return use_clock ? rtos_get_time_ticks() + offset : 0 + offset;
00100     }
00101 
00102     TimeService::ticks
00103     TimeService::getTicks( TimeService::ticks &relativeTime ) const
00104     {
00105         if ( relativeTime == 0 )
00106         {
00107             relativeTime = getTicks();
00108             return 0;
00109         }
00110         return ( getTicks() - relativeTime );
00111     }
00112 
00113     TimeService::ticks
00114     TimeService::ticksSince( TimeService::ticks relativeTime ) const
00115     {
00116         return ( getTicks() - relativeTime );
00117     }
00118 
00119 
00120     TimeService::Seconds
00121     TimeService::getSeconds( TimeService::ticks &relativeTime ) const
00122     {
00123         return nsecs_to_Seconds( ticks2nsecs( getTicks( relativeTime ) ) ) ;
00124     }
00125 
00126     TimeService::Seconds
00127     TimeService::secondsSince( TimeService::ticks relativeTime ) const
00128     {
00129         return nsecs_to_Seconds( ticks2nsecs( ticksSince( relativeTime ) ) ) ;
00130     }
00131 
00132     TimeService::Seconds
00133     TimeService::secondsChange( TimeService::Seconds delta )
00134     {
00135         offset += nsecs2ticks( Seconds_to_nsecs( delta ) );
00136         return nsecs_to_Seconds( ticks2nsecs( ticksSince( 0 ) ) ) ;
00137     }
00138 
00139     TimeService::nsecs
00140     TimeService::getNSecs() const
00141     {
00142         return rtos_get_time_ns();
00143     }
00144 
00145     TimeService::nsecs
00146     TimeService::getNSecs( TimeService::nsecs &relativeTime ) const
00147     {
00148         if ( relativeTime == 0 )
00149         {
00150             relativeTime = getNSecs();
00151             return 0;
00152         }
00153         return ( getNSecs() - relativeTime );
00154     }
00155 }


rtt
Author(s): RTT Developers
autogenerated on Mon Oct 6 2014 03:13:54