Main MRPT website > C++ reference for MRPT 1.9.9
Classes | Typedefs | Functions
Time and date functions (in #include

Detailed Description

<mrpt/system/datetime.h>)

Collaboration diagram for Time and date functions (in #include:

Classes

struct  mrpt::system::TTimeParts
 The parts of a date/time (it's like the standard 'tm' but with fractions of seconds). More...
 

Typedefs

typedef uint64_t mrpt::system::TTimeStamp
 A system independent time type, it holds the the number of 100-nanosecond intervals since January 1, 1601 (UTC). More...
 

Functions

mrpt::system::TTimeStamp mrpt::system::buildTimestampFromParts (const mrpt::system::TTimeParts &p)
 Builds a timestamp from the parts (Parts are in UTC) More...
 
mrpt::system::TTimeStamp mrpt::system::buildTimestampFromPartsLocalTime (const mrpt::system::TTimeParts &p)
 Builds a timestamp from the parts (Parts are in local time) More...
 
void mrpt::system::timestampToParts (TTimeStamp t, TTimeParts &p, bool localTime=false)
 Gets the individual parts of a date/time (days, hours, minutes, seconds) - UTC time or local time. More...
 
mrpt::system::TTimeStamp mrpt::system::getCurrentTime ()
 Returns the current (UTC) system time. More...
 
mrpt::system::TTimeStamp mrpt::system::now ()
 A shortcut for system::getCurrentTime. More...
 
mrpt::system::TTimeStamp mrpt::system::getCurrentLocalTime ()
 Returns the current (local) time. More...
 
mrpt::system::TTimeStamp mrpt::system::time_tToTimestamp (const double t)
 Transform from standard "time_t" (actually a double number, it can contain fractions of seconds) to TTimeStamp. More...
 
mrpt::system::TTimeStamp mrpt::system::time_tToTimestamp (const time_t &t)
 Transform from standard "time_t" to TTimeStamp. More...
 
double mrpt::system::timestampTotime_t (const mrpt::system::TTimeStamp t)
 Transform from TTimeStamp to standard "time_t" (actually a double number, it can contain fractions of seconds). More...
 
double mrpt::system::timestampToDouble (const mrpt::system::TTimeStamp t)
 Transform from TTimeStamp to standard "time_t" (actually a double number, it can contain fractions of seconds). More...
 
double mrpt::system::timeDifference (const mrpt::system::TTimeStamp t_first, const mrpt::system::TTimeStamp t_later)
 Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds. More...
 
double mrpt::system::now_double ()
 Returns the current time, as a double (fractional version of time_t) instead of a TTimeStamp. More...
 
mrpt::system::TTimeStamp mrpt::system::timestampAdd (const mrpt::system::TTimeStamp tim, const double num_seconds)
 Shifts a timestamp the given amount of seconds (>0: forwards in time, <0: backwards) More...
 
mrpt::system::TTimeStamp mrpt::system::secondsToTimestamp (const double nSeconds)
 Transform a time interval (in seconds) into TTimeStamp (e.g. More...
 
std::string mrpt::system::formatTimeInterval (const double timeSeconds)
 Returns a formated string with the given time difference (passed as the number of seconds), as a string [H]H:MM:SS.MILISECS. More...
 
std::string mrpt::system::dateTimeToString (const mrpt::system::TTimeStamp t)
 Convert a timestamp into this textual form (UTC time): YEAR/MONTH/DAY,HH:MM:SS.MMM. More...
 
std::string mrpt::system::dateTimeLocalToString (const mrpt::system::TTimeStamp t)
 Convert a timestamp into this textual form (in local time): YEAR/MONTH/DAY,HH:MM:SS.MMM. More...
 
std::string mrpt::system::dateToString (const mrpt::system::TTimeStamp t)
 Convert a timestamp into this textual form: YEAR/MONTH/DAY. More...
 
double mrpt::system::extractDayTimeFromTimestamp (const mrpt::system::TTimeStamp t)
 Returns the number of seconds ellapsed from midnight in the given timestamp. More...
 
std::string mrpt::system::timeToString (const mrpt::system::TTimeStamp t)
 Convert a timestamp into this textual form (UTC): HH:MM:SS.MMMMMM. More...
 
std::string mrpt::system::timeLocalToString (const mrpt::system::TTimeStamp t, unsigned int secondFractionDigits=6)
 Convert a timestamp into this textual form (in local time): HH:MM:SS.MMMMMM. More...
 
std::string mrpt::system::intervalFormat (const double seconds)
 This function implements time interval formatting: Given a time in seconds, it will return a string describing the interval with the most appropriate unit. More...
 

Typedef Documentation

◆ TTimeStamp

A system independent time type, it holds the the number of 100-nanosecond intervals since January 1, 1601 (UTC).

See also
system::getCurrentTime, system::timeDifference, INVALID_TIMESTAMP, TTimeParts

Definition at line 32 of file datetime.h.

Function Documentation

◆ buildTimestampFromParts()

TTimeStamp mrpt::system::buildTimestampFromParts ( const mrpt::system::TTimeParts p)

◆ buildTimestampFromPartsLocalTime()

TTimeStamp mrpt::system::buildTimestampFromPartsLocalTime ( const mrpt::system::TTimeParts p)

Builds a timestamp from the parts (Parts are in local time)

See also
timestampToParts, buildTimestampFromParts

Definition at line 150 of file datetime.cpp.

References mrpt::system::time_tToTimestamp().

Here is the call graph for this function:

◆ dateTimeLocalToString()

string mrpt::system::dateTimeLocalToString ( const mrpt::system::TTimeStamp  t)

Convert a timestamp into this textual form (in local time): YEAR/MONTH/DAY,HH:MM:SS.MMM.

See also
dateTimeToString

Definition at line 269 of file datetime.cpp.

References mrpt::format(), and INVALID_TIMESTAMP.

Referenced by mrpt::nav::CWaypointsNavigator::checkHasReachedTarget(), and mrpt::hwdrivers::CNTRIPEmitter::initialize().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dateTimeToString()

string mrpt::system::dateTimeToString ( const mrpt::system::TTimeStamp  t)

Convert a timestamp into this textual form (UTC time): YEAR/MONTH/DAY,HH:MM:SS.MMM.

See also
dateTimeLocalToString

Definition at line 247 of file datetime.cpp.

References mrpt::format(), and INVALID_TIMESTAMP.

Referenced by mrpt::obs::CObservation::getDescriptionAsText(), mrpt::obs::CObservationGPS::getDescriptionAsText(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initResultsFile().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dateToString()

string mrpt::system::dateToString ( const mrpt::system::TTimeStamp  t)

Convert a timestamp into this textual form: YEAR/MONTH/DAY.

Definition at line 356 of file datetime.cpp.

References mrpt::format(), and INVALID_TIMESTAMP.

Here is the call graph for this function:

◆ extractDayTimeFromTimestamp()

double mrpt::system::extractDayTimeFromTimestamp ( const mrpt::system::TTimeStamp  t)

Returns the number of seconds ellapsed from midnight in the given timestamp.

Definition at line 290 of file datetime.cpp.

References ASSERT_, ASSERTMSG_, INVALID_TIMESTAMP, MRPT_END, and MRPT_START.

Referenced by mrpt::maps::CLandmarksMap::saveToTextFile().

Here is the caller graph for this function:

◆ formatTimeInterval()

string mrpt::system::formatTimeInterval ( const double  timeSeconds)

Returns a formated string with the given time difference (passed as the number of seconds), as a string [H]H:MM:SS.MILISECS.

See also
unitsFormat

Definition at line 231 of file datetime.cpp.

References mrpt::format().

Referenced by mrpt::hmtslam::CHMTSLAM::generateLogFiles(), and mrpt::slam::CMetricMapBuilderICP::processObservation().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCurrentLocalTime()

mrpt::system::TTimeStamp mrpt::system::getCurrentLocalTime ( )

Returns the current (local) time.

See also
now,getCurrentTime

Definition at line 173 of file datetime.cpp.

References THROW_EXCEPTION, and mrpt::system::time_tToTimestamp().

Referenced by mrpt::hwdrivers::CEnoseModular::getObservation(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initResultsFile().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCurrentTime()

mrpt::system::TTimeStamp mrpt::system::getCurrentTime ( )

◆ intervalFormat()

std::string mrpt::system::intervalFormat ( const double  seconds)

This function implements time interval formatting: Given a time in seconds, it will return a string describing the interval with the most appropriate unit.

E.g.: 1.23 year, 3.50 days, 9.3 hours, 5.3 minutes, 3.34 sec, 178.1 ms, 87.1 us.

See also
unitsFormat

E.g.: 1.23 year, 3.50 days, 9.3 hours, 5.3 minutes, 3.34 sec, 178.1 ms, 87.1 us.

Definition at line 375 of file datetime.cpp.

References mrpt::format().

Here is the call graph for this function:

◆ now()

mrpt::system::TTimeStamp mrpt::system::now ( )
inline

A shortcut for system::getCurrentTime.

See also
getCurrentTime, getCurrentLocalTime

Definition at line 76 of file datetime.h.

References mrpt::system::getCurrentTime().

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::compress::zip::compress_gz_data_block(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::computeMap(), mrpt::detectors::CObjectDetection::detectObjects(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getCurrentPoseAndSpeeds(), mrpt::nav::CRobot2NavInterfaceForSimulator_DiffDriven::getCurrentPoseAndSpeeds(), mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), rp::arch::getus(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::nav::CAbstractPTGBasedReactive::impl_waypoint_is_reachable(), mrpt::hwdrivers::CGPSInterface::implement_parser_NOVATEL_OEM6(), IMPLEMENTS_SERIALIZABLE(), mrpt::slam::CMetricMapBuilderICP::initialize(), mrpt::hwdrivers::CIMUXSens::initialize(), mrpt::hwdrivers::CNTRIPEmitter::initialize(), mrpt::hwdrivers::CVelodyneScanner::internal_read_PCAP_packet(), mrpt::hwdrivers::CVelodyneScanner::internal_receive_UDP_packet(), rp::hal::Locker::lock(), mrpt::system::MRPT_getCompilationDate(), mrpt::nav::CWaypointsNavigator::navigateWaypoints(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), run_pc_filter_test(), run_rnav_test(), mrpt::maps::CGasConcentrationGridMap2D::simulateAdvection(), PacketStamper::stampPacket(), TEST(), rp::hal::Event::wait(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().

Here is the call graph for this function:

◆ now_double()

double mrpt::system::now_double ( )
inline

Returns the current time, as a double (fractional version of time_t) instead of a TTimeStamp.

See also
now(), timestampTotime_t()

Definition at line 119 of file datetime.h.

References mrpt::system::getCurrentTime(), and mrpt::system::timestampTotime_t().

Here is the call graph for this function:

◆ secondsToTimestamp()

mrpt::system::TTimeStamp mrpt::system::secondsToTimestamp ( const double  nSeconds)

◆ time_tToTimestamp() [1/2]

mrpt::system::TTimeStamp mrpt::system::time_tToTimestamp ( const double  t)

Transform from standard "time_t" (actually a double number, it can contain fractions of seconds) to TTimeStamp.

See also
timestampTotime_t

Definition at line 49 of file datetime.cpp.

Referenced by mrpt::system::buildTimestampFromParts(), mrpt::system::buildTimestampFromPartsLocalTime(), mrpt::system::getCurrentLocalTime(), mrpt::system::getCurrentTime(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::poses::CPoseInterpolatorBase< 3 >::loadFromTextFile(), and TEST().

Here is the caller graph for this function:

◆ time_tToTimestamp() [2/2]

mrpt::system::TTimeStamp mrpt::system::time_tToTimestamp ( const time_t &  t)

Transform from standard "time_t" to TTimeStamp.

See also
timestampTotime_t

Definition at line 43 of file datetime.cpp.

◆ timeDifference()

double mrpt::system::timeDifference ( const mrpt::system::TTimeStamp  t_first,
const mrpt::system::TTimeStamp  t_later 
)

◆ timeLocalToString()

string mrpt::system::timeLocalToString ( const mrpt::system::TTimeStamp  t,
unsigned int  secondFractionDigits = 6 
)

Convert a timestamp into this textual form (in local time): HH:MM:SS.MMMMMM.

Definition at line 314 of file datetime.cpp.

References mrpt::format(), and INVALID_TIMESTAMP.

Referenced by mrpt::hwdrivers::CNTRIPEmitter::doProcess().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ timestampAdd()

mrpt::system::TTimeStamp mrpt::system::timestampAdd ( const mrpt::system::TTimeStamp  tim,
const double  num_seconds 
)

Shifts a timestamp the given amount of seconds (>0: forwards in time, <0: backwards)

See also
secondsToTimestamp

Definition at line 198 of file datetime.cpp.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), run_pc_filter_test(), and velodyne_scan_to_pointcloud().

Here is the caller graph for this function:

◆ timestampToDouble()

double mrpt::system::timestampToDouble ( const mrpt::system::TTimeStamp  t)
inline

Transform from TTimeStamp to standard "time_t" (actually a double number, it can contain fractions of seconds).

This function is just an (inline) alias of timestampTotime_t(), with a more significant name.

See also
time_tToTimestamp, secondsToTimestamp

Definition at line 105 of file datetime.h.

References mrpt::system::timestampTotime_t().

Here is the call graph for this function:

◆ timestampToParts()

void mrpt::system::timestampToParts ( TTimeStamp  t,
TTimeParts p,
bool  localTime = false 
)

Gets the individual parts of a date/time (days, hours, minutes, seconds) - UTC time or local time.

See also
buildTimestampFromParts

Definition at line 103 of file datetime.cpp.

References ASSERT_, ASSERTMSG_, and mrpt::system::timestampTotime_t().

Referenced by mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::obs::gnss::UTC_time::getAsTimestamp(), mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), and mrpt::hwdrivers::CVelodyneScanner::receivePackets().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ timestampTotime_t()

double mrpt::system::timestampTotime_t ( const mrpt::system::TTimeStamp  t)

◆ timeToString()

string mrpt::system::timeToString ( const mrpt::system::TTimeStamp  t)

Convert a timestamp into this textual form (UTC): HH:MM:SS.MMMMMM.

Definition at line 337 of file datetime.cpp.

References mrpt::format(), and INVALID_TIMESTAMP.

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::_execGraphSlamStep(), mrpt::hwdrivers::CGPSInterface::doProcess(), and CGraphSlamHandler< GRAPH_T >::initOutputDir().

Here is the call graph for this function:
Here is the caller graph for this function:



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019