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 BASE_IMPEXP | mrpt::system::buildTimestampFromParts (const mrpt::system::TTimeParts &p) |
Builds a timestamp from the parts (Parts are in UTC) More... | |
mrpt::system::TTimeStamp BASE_IMPEXP | mrpt::system::buildTimestampFromPartsLocalTime (const mrpt::system::TTimeParts &p) |
Builds a timestamp from the parts (Parts are in local time) More... | |
void BASE_IMPEXP | 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 BASE_IMPEXP | 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 BASE_IMPEXP | mrpt::system::getCurrentLocalTime () |
Returns the current (local) time. More... | |
mrpt::system::TTimeStamp BASE_IMPEXP | 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 BASE_IMPEXP | mrpt::system::time_tToTimestamp (const time_t &t) |
Transform from standard "time_t" to TTimeStamp. More... | |
double BASE_IMPEXP | 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 BASE_IMPEXP | 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 BASE_IMPEXP | 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 BASE_IMPEXP | mrpt::system::secondsToTimestamp (const double nSeconds) |
Transform a time interval (in seconds) into TTimeStamp (e.g. More... | |
std::string BASE_IMPEXP | 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 BASE_IMPEXP | 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 BASE_IMPEXP | 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 BASE_IMPEXP | mrpt::system::dateToString (const mrpt::system::TTimeStamp t) |
Convert a timestamp into this textual form: YEAR/MONTH/DAY. More... | |
double BASE_IMPEXP | mrpt::system::extractDayTimeFromTimestamp (const mrpt::system::TTimeStamp t) |
Returns the number of seconds ellapsed from midnight in the given timestamp. More... | |
std::string BASE_IMPEXP | mrpt::system::timeToString (const mrpt::system::TTimeStamp t) |
Convert a timestamp into this textual form (UTC): HH:MM:SS.MMMMMM. More... | |
std::string BASE_IMPEXP | 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 BASE_IMPEXP | 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 uint64_t mrpt::system::TTimeStamp |
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1, 1601 (UTC).
Definition at line 30 of file datetime.h.
TTimeStamp mrpt::system::buildTimestampFromParts | ( | const mrpt::system::TTimeParts & | p | ) |
Builds a timestamp from the parts (Parts are in UTC)
Definition at line 127 of file datetime.cpp.
References mrpt::system::time_tToTimestamp(), and mrpt::system::os::timegm().
Referenced by mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::obs::gnss::UTC_time::getAsTimestamp(), mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp(), mrpt::obs::gnss::Message_NMEA_ZDA::getDateAsTimestamp(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), and mrpt::obs::CObservationGPS::GPS_time_to_UTC().
TTimeStamp mrpt::system::buildTimestampFromPartsLocalTime | ( | const mrpt::system::TTimeParts & | p | ) |
Builds a timestamp from the parts (Parts are in local time)
Definition at line 150 of file datetime.cpp.
References mrpt::system::time_tToTimestamp().
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.
Definition at line 274 of file datetime.cpp.
References mrpt::format(), and INVALID_TIMESTAMP.
Referenced by mrpt::nav::CWaypointsNavigator::checkHasReachedTarget(), and mrpt::hwdrivers::CNTRIPEmitter::initialize().
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.
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().
string mrpt::system::dateToString | ( | const mrpt::system::TTimeStamp | t | ) |
Convert a timestamp into this textual form: YEAR/MONTH/DAY.
Definition at line 369 of file datetime.cpp.
References mrpt::format(), and INVALID_TIMESTAMP.
double mrpt::system::extractDayTimeFromTimestamp | ( | const mrpt::system::TTimeStamp | t | ) |
Returns the number of seconds ellapsed from midnight in the given timestamp.
Definition at line 299 of file datetime.cpp.
References ASSERT_, ASSERTMSG_, INVALID_TIMESTAMP, MRPT_END, and MRPT_START.
Referenced by mrpt::maps::CLandmarksMap::saveToTextFile().
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.
Definition at line 227 of file datetime.cpp.
References mrpt::format().
Referenced by mrpt::hmtslam::CHMTSLAM::generateLogFiles(), and mrpt::slam::CMetricMapBuilderICP::processObservation().
mrpt::system::TTimeStamp mrpt::system::getCurrentLocalTime | ( | ) |
Returns the current (local) time.
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().
mrpt::system::TTimeStamp mrpt::system::getCurrentTime | ( | ) |
Returns the current (UTC) system time.
Definition at line 71 of file datetime.cpp.
References mrpt::system::time_tToTimestamp().
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::_execGraphSlamStep(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CGillAnemometer::doProcess(), mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), CGraphSlamHandler< GRAPH_T >::initOutputDir(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initResultsFile(), mrpt::system::now(), mrpt::system::now_double(), mrpt::nav::CAbstractNavigator::performNavigationStepNavigating(), mrpt::nav::CAbstractNavigator::processNavigateCommand(), mrpt::random::CRandomGenerator::randomize(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), and mrpt::maps::CLandmarksMap::simulateRangeBearingReadings().
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.
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 391 of file datetime.cpp.
References mrpt::format().
|
inline |
A shortcut for system::getCurrentTime.
Definition at line 70 of file datetime.h.
References mrpt::system::getCurrentTime().
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::maps::CGasConcentrationGridMap2D::CGasConcentrationGridMap2D(), 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::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getCurrentPoseAndSpeeds(), mrpt::nav::CRobot2NavInterfaceForSimulator_DiffDriven::getCurrentPoseAndSpeeds(), mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp(), mrpt::hwdrivers::CRaePID::getFullInfo(), 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(), 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().
|
inline |
Returns the current time, as a double
(fractional version of time_t) instead of a TTimeStamp
.
Definition at line 104 of file datetime.h.
References mrpt::system::getCurrentTime(), and mrpt::system::timestampTotime_t().
mrpt::system::TTimeStamp mrpt::system::secondsToTimestamp | ( | const double | nSeconds | ) |
Transform a time interval (in seconds) into TTimeStamp (e.g.
which can be added to an existing valid timestamp)
Definition at line 219 of file datetime.cpp.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveInterpolatedToTextFile(), and TEST().
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.
Definition at line 48 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().
mrpt::system::TTimeStamp mrpt::system::time_tToTimestamp | ( | const time_t & | t | ) |
Transform from standard "time_t" to TTimeStamp.
Definition at line 43 of file datetime.cpp.
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.
Definition at line 205 of file datetime.cpp.
References ASSERT_, INVALID_TIMESTAMP, MRPT_END, and MRPT_START.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::_execGraphSlamStep(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::poses::CRobot2DPoseEstimator::getCurrentEstimate(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::nav::CAbstractPTGBasedReactive::impl_waypoint_is_reachable(), mrpt::obs::CObservationGasSensors::CMOSmodel::inverse_MOSmodeling(), mrpt::topography::path_from_rtk_gps(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::nav::CAbstractNavigator::performNavigationStepNavigating(), mrpt::poses::CRobot2DPoseEstimator::processUpdateNewOdometry(), mrpt::poses::CRobot2DPoseEstimator::processUpdateNewPoseLocalization(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), mrpt::maps::CGasConcentrationGridMap2D::simulateAdvection(), mrpt::nav::CAbstractNavigator::updateCurrentPoseAndSpeeds(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().
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 321 of file datetime.cpp.
References mrpt::format(), and INVALID_TIMESTAMP.
Referenced by mrpt::hwdrivers::CNTRIPEmitter::doProcess().
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)
Definition at line 197 of file datetime.cpp.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), run_pc_filter_test(), and velodyne_scan_to_pointcloud().
|
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.
Definition at line 98 of file datetime.h.
References mrpt::system::timestampTotime_t().
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.
Definition at line 101 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().
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).
Definition at line 53 of file datetime.cpp.
Referenced by mrpt::obs::CObservation::getDescriptionAsText(), mrpt::obs::CObservationGPS::getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::poses::CPoseInterpolatorBase< 3 >::interpolate(), mrpt::system::now_double(), mrpt::obs::CObservationGasSensors::CMOSmodel::save_log_map(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveInterpolatedToTextFile(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveToTextFile(), mrpt::hwdrivers::CCameraSensor::thread_save_images(), mrpt::system::timestampToDouble(), and mrpt::system::timestampToParts().
string mrpt::system::timeToString | ( | const mrpt::system::TTimeStamp | t | ) |
Convert a timestamp into this textual form (UTC): HH:MM:SS.MMMMMM.
Definition at line 347 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().
Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019 |