Time.cpp
Go to the documentation of this file.
00001 /*
00002  * Time.cpp
00003  *
00004  *  Created on: Oct 26, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #include <telekyb_base/Time/Time.hpp>
00009 
00010 // ROS
00011 #include <ros/assert.h>
00012 
00013 // Time
00014 #include <time.h>
00015 
00016 // boost
00017 #include <boost/lexical_cast.hpp>
00018 
00019 
00020 // Apple Mac Timefix
00021 #ifdef __MACH__
00022 #include <mach/clock.h>
00023 #include <mach/mach.h>
00024 #endif
00025 
00026 namespace TELEKYB_NAMESPACE
00027 {
00028 
00029 Time::Time(){
00030 //      struct timeval current;
00031 //      gettimeofday(&current,NULL); // not as accurate.
00032 #ifdef __MACH__ // OS X does not have clock_gettime, use clock_get_time
00033         clock_serv_t cclock;
00034         mach_timespec_t mts;
00035         host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock);
00036         clock_get_time(cclock, &mts);
00037         mach_port_deallocate(mach_task_self(), cclock);
00038         _sec = mts.tv_sec;
00039         _usec = mts.tv_nsec / 1000; // to usec
00040 #else
00041         struct timespec current;
00042         clock_gettime(CLOCK_REALTIME, &current);
00043         _sec  = current.tv_sec;
00044         _usec = current.tv_nsec / 1000; // to usec
00045 #endif
00046 }
00047 
00048 
00049 Time::Time(long int s,long int u){
00050         ROS_ASSERT(u>=0);
00051         _sec  = s + u/TIME_RESOLUTION;
00052         _usec = u%TIME_RESOLUTION;
00053 }
00054 
00055 Time::Time(double t){
00056         if(t >= 0.0){
00057                 _sec  = (long int) t;
00058                 _usec = (long int) (fmod(t,1)*1000000.0);
00059         }else{
00060                 _sec  = (long int) (t - 1.0);
00061                 _usec = (long int) ((1.0 + fmod(t,1))*1000000.0);
00062         }
00063         //?
00064         //*this = Time(_sec,_usec);
00065 }
00066 
00067 Time::Time(const Time& t) {
00068         _sec  = t._sec;
00069         _usec = t._usec;
00070 }
00071 
00072 Time::Time(const ros::Time& time)
00073 {
00074         _sec = time.sec;
00075         _usec = time.nsec / 1000;
00076 }
00077 
00078 Time::~Time() {
00079 
00080 }
00081 
00082 Time& Time::operator=(const Time& t){
00083         if (this != &t){      // Not necessary in this case but it is useful to don't forget it
00084                 _sec  = t._sec;
00085                 _usec = t._usec;
00086         }
00087         return *this;
00088 }
00089 
00090 Time& Time::operator+=(const Time& t) {
00091         _sec  += (t._sec + ((_usec + t._usec)/TIME_RESOLUTION));
00092         _usec = (_usec + t._usec)%TIME_RESOLUTION;
00093         return *this;
00094 }
00095 
00096 Time& Time::operator-=(const Time& t) {
00097         if(_usec < t._usec){ /*negative difference*/
00098                 _usec   +=  (TIME_RESOLUTION  - t._usec);
00099                 _sec    -=      (t._sec + 1);
00100         }else{
00101                 _usec   -=      t._usec;
00102                 _sec    -=      t._sec;
00103         }
00104         return *this;
00105 }
00106 
00107 /*const */Time Time::operator+(const Time &other) const {
00108         return Time(*this) += other;
00109 }
00110 
00111 /*const */Time Time::operator-(const Time &other) const {
00112         return Time(*this) -= other;
00113 }
00114 
00115 Time& Time::operator*=(double scalar) {
00116         double decimalTime = toDSec();
00117         decimalTime *= scalar;
00118         Time time(decimalTime);
00119         _usec   = time.usec();
00120         _sec    = time.sec();
00121         return *this;
00122 }
00123 
00124 Time& Time::operator*(double scalar) {
00125         return Time(*this) *= scalar;
00126 }
00127 
00128 bool Time::operator==(const Time &other) const {
00129         return (_sec == other._sec) && (_usec == other._usec);
00130 }
00131 
00132 
00133 bool Time::operator!=(const Time &other) const {
00134         return !(*this == other);
00135 }
00136 
00137 
00138 bool Time::operator>(const Time &other) const {
00139         if(_sec > other._sec ){
00140                 return true;
00141         }else{
00142                 if((_sec == other._sec )&&( _usec > other._usec )){
00143                         return true;
00144                 }else{
00145                         return false;
00146                 }
00147         }
00148 }
00149 
00150 
00151 bool Time::operator<(const Time &other) const {
00152         return( (!(*this > other)) && (!(*this == other)) );
00153 }
00154 
00155 
00156 bool Time::operator>=(const Time &other) const {
00157         return !(*this < other);
00158 }
00159 
00160 
00161 bool Time::operator<=(const Time &other) const {
00162         return !(*this > other);
00163 }
00164 
00165 
00166 long int Time::sec () {
00167         return _sec;
00168 }
00169 long int Time::usec () {
00170         return _usec;
00171 }
00172 
00173 bool Time::isZero() const {
00174         return (*this == Time::Zero());
00175 }
00176 
00177 void Time::sleep() {
00178         // implemented with nanosleep
00179         timespec req = { _sec, _usec * 1000 }; // to nsec
00180         timespec rem = { 0, 0 };
00181 
00182         while (nanosleep(&req, &rem)) {
00183                 req = rem;
00184         }
00185 }
00186 
00188 Time Time::Zero() {
00189         return Time(0,0);
00190 }
00191 
00192 double Time::toDSec(){
00193         return (double) _sec + ((double) _usec / TIME_RESOLUTION );
00194 }
00195 
00196 
00197 double Time::frequency(){
00198         return 1.0/ toDSec();
00199 }
00200 
00201 ros::Time Time::toRosTime() const
00202 {
00203         return ros::Time(_sec,_usec*1000);
00204 }
00205 
00206 std::string Time::toString(){
00207 //      stringstream su;
00208 //      su.fill('0');
00209 //      su.width(6);
00210 //      su << _usec;
00211 //      stringstream s;
00212 //      s << _sec << " sec, " << su.str() << " usec" ;
00213         return std::string( boost::lexical_cast<std::string>(_sec) + " sec, " + boost::lexical_cast<std::string>(_usec) + " usec");
00214 }
00215 
00216 
00217 std::string Time::freqToString(){
00218 //      stringstream s;
00219 //      s.precision(2);
00220 //      s.setf(ios::fixed,ios::floatfield);
00221 //      s << freq() << " Hz";
00222         return std::string( boost::lexical_cast<std::string>(frequency()) + " Hz" );
00223 }
00224 
00225 std::string Time::dSecToString(){
00226 //      stringstream s;
00227 //      s.precision(3);
00228 //      s.setf(ios::fixed,ios::floatfield);
00229 //      s << dCast();
00230         return std::string( boost::lexical_cast<std::string>( toDSec()) );
00231 }
00232 
00233 std::string Time::dateTimeToString() {
00234 
00235         time_t rawtime;
00236         struct tm * timeinfo;
00237         char buffer [80];
00238         rawtime = _sec;
00239         timeinfo = localtime ( &rawtime );
00240         strftime (buffer,80,"%Y-%m-%d_%H-%M-%S",timeinfo);
00241 //      stringstream s;
00242 //      s.precision(3);
00243 //      s.setf(ios::fixed,ios::floatfield);
00244         std::string strTime(buffer);
00245         return strTime;
00246 }
00247 
00248 } /* namespace telekyb */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


telekyb_base
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:12:34