MRPT
2.0.1
|
Header: #include <mrpt/system/datetime.h>
.
Library: [mrpt-system]
Defines types and functions to handle cross-platform timestamps. The basic type is mrpt::system::TTimeStamp, representing a high-resolution (100ns) Clock::time_point, compatible with all C++11 std::chrono functions.
There are also functions to convert forth and back to a double
representation of timestamps: numbers just like UNIX epoch timestamps but with decimals for the fractionary part of seconds.
Classes | |
struct | mrpt::system::TTimeParts |
The parts of a date/time (it's like the standard 'tm' but with fractions of seconds). More... | |
Macros | |
#define | INVALID_TIMESTAMP mrpt::Clock::time_point() |
Represents an invalid timestamp, where applicable. More... | |
Typedefs | |
using | mrpt::system::TTimeStamp = mrpt::Clock::time_point |
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1, 1601 (UTC) as a mrpt::Clock::time_point (uint64_t). 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::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) noexcept |
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) noexcept |
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... | |
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.MILLISECONDS. 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... | |
std::ostream & | mrpt::system::operator<< (std::ostream &o, const TTimeStamp &t) |
Textual representation of a TTimeStamp as the plain number in time_since_epoch().count() More... | |
#define INVALID_TIMESTAMP mrpt::Clock::time_point() |
Represents an invalid timestamp, where applicable.
Definition at line 43 of file datetime.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::_execGraphSlamStep(), mrpt::nav::CWaypointsNavigator::checkHasReachedTarget(), mrpt::obs::CObservationGPS::clear(), mrpt::system::dateTimeLocalToString(), mrpt::system::dateTimeToString(), mrpt::system::dateToString(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::system::extractDayTimeFromTimestamp(), mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::obs::CRawlog::findObservationsByClassInRange(), mrpt::obs::CObservationVelodyneScan::generatePointCloudAlongSE3Trajectory(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getTimeStamp(), mrpt::nav::CAbstractPTGBasedReactive::impl_waypoint_is_reachable(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initClass(), mrpt::nav::CAbstractPTGBasedReactive::initialize(), mrpt::hwdrivers::CVelodyneScanner::initialize(), mrpt::hwdrivers::C2DRangeFinderAbstract::internal_notifyGoodScanNow(), mrpt::hwdrivers::C2DRangeFinderAbstract::internal_notifyNoScanReceived(), mrpt::hwdrivers::CVelodyneScanner::internal_read_PCAP_packet(), mrpt::hwdrivers::CVelodyneScanner::internal_receive_UDP_packet(), mrpt::nav::CAbstractPTGBasedReactive::TSentVelCmd::isValid(), mrpt::poses::FrameTransformer< 2 >::lookupTransform(), mrpt::nav::CWaypointsNavigator::onNavigateCommandReceived(), mrpt::slam::CMetricMapBuilderICP::processObservation(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), mrpt::nav::CAbstractPTGBasedReactive::TSentVelCmd::reset(), mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::maps::CLandmarksMap::saveToTextFile(), mrpt::obs::CObservationRFID::serializeFrom(), mrpt::obs::CObservationBeaconRanges::serializeFrom(), mrpt::obs::CObservationGasSensors::serializeFrom(), mrpt::obs::CObservationWirelessPower::serializeFrom(), mrpt::obs::CActionRobotMovement3D::serializeFrom(), mrpt::obs::CObservationRange::serializeFrom(), mrpt::obs::CObservationBearingRange::serializeFrom(), mrpt::obs::CObservationWindSensor::serializeFrom(), mrpt::obs::CActionRobotMovement2D::serializeFrom(), mrpt::obs::CObservationBatteryState::serializeFrom(), mrpt::obs::CObservationStereoImages::serializeFrom(), mrpt::obs::CSensoryFrame::serializeFrom(), mrpt::obs::CObservationGPS::serializeFrom(), mrpt::system::timeDifference(), mrpt::system::timeLocalToString(), and mrpt::system::timeToString().
using mrpt::system::TTimeStamp = typedef mrpt::Clock::time_point |
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1, 1601 (UTC) as a mrpt::Clock::time_point (uint64_t).
Definition at line 40 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 74 of file datetime.cpp.
References mrpt::system::TTimeParts::day, mrpt::system::TTimeParts::day_of_week, mrpt::system::TTimeParts::daylight_saving, mrpt::system::TTimeParts::hour, mrpt::system::TTimeParts::minute, mrpt::system::TTimeParts::month, mrpt::system::TTimeParts::second, mrpt::system::time_tToTimestamp(), mrpt::system::os::timegm(), and mrpt::system::TTimeParts::year.
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 99 of file datetime.cpp.
References mrpt::system::TTimeParts::day, mrpt::system::TTimeParts::day_of_week, mrpt::system::TTimeParts::daylight_saving, mrpt::system::TTimeParts::hour, mrpt::system::TTimeParts::minute, mrpt::system::TTimeParts::month, mrpt::system::TTimeParts::second, mrpt::system::time_tToTimestamp(), and mrpt::system::TTimeParts::year.
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 176 of file datetime.cpp.
References calcSecFractions(), mrpt::format(), and INVALID_TIMESTAMP.
Referenced by mrpt::nav::CWaypointsNavigator::checkHasReachedTarget(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), 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 154 of file datetime.cpp.
References calcSecFractions(), mrpt::format(), and INVALID_TIMESTAMP.
Referenced by mrpt::obs::CAction::getDescriptionAsText(), mrpt::obs::CObservation::getDescriptionAsText(), mrpt::obs::CObservationRotatingScan::getDescriptionAsText(), mrpt::obs::CObservationGPS::getDescriptionAsText(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initResultsFile(), and TEST().
string mrpt::system::dateToString | ( | const mrpt::system::TTimeStamp | t | ) |
Convert a timestamp into this textual form: YEAR/MONTH/DAY.
Definition at line 263 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 197 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.MILLISECONDS.
Definition at line 124 of file datetime.cpp.
References mrpt::format().
Referenced by mrpt::hmtslam::CHMTSLAM::generateLogFiles(), and mrpt::slam::CMetricMapBuilderICP::processObservation().
|
inline |
Returns the current (UTC) system time.
Definition at line 82 of file datetime.h.
References mrpt::Clock::now().
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::_execGraphSlamStep(), mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CGillAnemometer::doProcess(), mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::system::now_double(), mrpt::nav::CAbstractNavigator::performNavigationStepNavigating(), mrpt::nav::CAbstractNavigator::processNavigateCommand(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), and TEST().
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 283 of file datetime.cpp.
References mrpt::format().
|
inline |
A shortcut for system::getCurrentTime.
Definition at line 86 of file datetime.h.
References mrpt::Clock::now().
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::io::zip::compress_gz_data_block(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::computeMap(), mrpt::nav::CWaypointsNavigator::CWaypointsNavigator(), 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::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::CCameraSensor::getNextFrame(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::nav::CAbstractPTGBasedReactive::impl_waypoint_is_reachable(), mrpt::hwdrivers::CGPSInterface::implement_parser_NOVATEL_OEM6(), IMPLEMENTS_SERIALIZABLE(), mrpt::hwdrivers::CIMUXSens::initialize(), mrpt::hwdrivers::CNTRIPEmitter::initialize(), mrpt::hwdrivers::C2DRangeFinderAbstract::internal_notifyGoodScanNow(), mrpt::hwdrivers::C2DRangeFinderAbstract::internal_notifyNoScanReceived(), mrpt::hwdrivers::CVelodyneScanner::internal_read_PCAP_packet(), mrpt::hwdrivers::CVelodyneScanner::internal_receive_UDP_packet(), mrpt::system::MRPT_getCompilationDate(), mrpt::nav::CWaypointsNavigator::navigateWaypoints(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), mrpt::apps::RawlogGrabberApp::run(), run_pc_filter_test(), run_rnav_test(), mrpt::maps::CGasConcentrationGridMap2D::simulateAdvection(), TEST(), 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 139 of file datetime.h.
References mrpt::system::getCurrentTime(), and mrpt::system::timestampTotime_t().
std::ostream & mrpt::system::operator<< | ( | std::ostream & | o, |
const TTimeStamp & | t | ||
) |
Textual representation of a TTimeStamp as the plain number in time_since_epoch().count()
Definition at line 303 of file datetime.cpp.
|
inline |
Transform from standard "time_t" (actually a double number, it can contain fractions of seconds) to TTimeStamp.
Definition at line 91 of file datetime.h.
References mrpt::Clock::fromDouble().
Referenced by mrpt::system::buildTimestampFromParts(), mrpt::system::buildTimestampFromPartsLocalTime(), mrpt::ros1bridge::fromROS(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::poses::CPoseInterpolatorBase< 3 >::loadFromTextFile(), TEST(), and mrpt::system::time_tToTimestamp().
mrpt::system::TTimeStamp mrpt::system::time_tToTimestamp | ( | const time_t & | t | ) |
Transform from standard "time_t" to TTimeStamp.
Definition at line 45 of file datetime.cpp.
References mrpt::system::time_tToTimestamp().
|
inline |
Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds.
Definition at line 123 of file datetime.h.
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::apps::RawlogGrabberApp::dump_verbose_info(), mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::poses::CRobot2DPoseEstimator::getCurrentEstimate(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::apps::ICP_SLAM_App_Live::impl_get_next_observations(), mrpt::nav::CAbstractPTGBasedReactive::impl_waypoint_is_reachable(), mrpt::hwdrivers::C2DRangeFinderAbstract::internal_notifyGoodScanNow(), mrpt::hwdrivers::C2DRangeFinderAbstract::internal_notifyNoScanReceived(), mrpt::obs::CObservationGasSensors::CMOSmodel::inverse_MOSmodeling(), mrpt::topography::path_from_rtk_gps(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::nav::CAbstractNavigator::performNavigationStepNavigating(), mrpt::apps::RawlogGrabberApp::process_observations_for_sf(), mrpt::poses::CRobot2DPoseEstimator::processUpdateNewOdometry(), mrpt::poses::CRobot2DPoseEstimator::processUpdateNewPoseLocalization(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), mrpt::maps::CGasConcentrationGridMap2D::simulateAdvection(), mrpt::system::CTimeLoggerEntry::stop(), TEST(), 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 222 of file datetime.cpp.
References calcSecFractions(), mrpt::format(), and INVALID_TIMESTAMP.
Referenced by mrpt::hwdrivers::CNTRIPEmitter::doProcess(), and mrpt::system::COutputLogger::TMsg::getAsString().
|
inline |
Shifts a timestamp the given amount of seconds (>0: forwards in time, <0: backwards)
Definition at line 146 of file datetime.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), run_pc_filter_test(), TEST(), and velodyne_scan_to_pointcloud().
|
inlinenoexcept |
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 116 of file datetime.h.
References mrpt::system::timestampTotime_t().
Referenced by mrpt::apps::KFSLAMApp::Run_KF_SLAM(), and TEST().
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 50 of file datetime.cpp.
References ASSERT_, ASSERTMSG_, mrpt::system::TTimeParts::day, mrpt::system::TTimeParts::day_of_week, mrpt::system::TTimeParts::daylight_saving, mrpt::system::TTimeParts::hour, mrpt::system::TTimeParts::minute, mrpt::system::TTimeParts::month, mrpt::system::TTimeParts::second, mrpt::system::timestampTotime_t(), and mrpt::system::TTimeParts::year.
Referenced by mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::obs::gnss::UTC_time::getAsTimestamp(), mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), and mrpt::apps::RawlogGrabberApp::run().
|
inlinenoexcept |
Transform from TTimeStamp to standard "time_t" (actually a double number, it can contain fractions of seconds).
Definition at line 105 of file datetime.h.
References mrpt::Clock::toDouble().
Referenced by mrpt::obs::CAction::getDescriptionAsText(), mrpt::obs::CObservationGPS::getDescriptionAsText(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::system::now_double(), mrpt::obs::CObservationGasSensors::CMOSmodel::save_log_map(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveInterpolatedToTextFile(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveToTextFile(), TEST(), mrpt::hwdrivers::CCameraSensor::thread_save_images(), mrpt::system::timestampToDouble(), mrpt::system::timestampToParts(), and mrpt::ros1bridge::toROS().
string mrpt::system::timeToString | ( | const mrpt::system::TTimeStamp | t | ) |
Convert a timestamp into this textual form (UTC): HH:MM:SS.MMMMMM.
Definition at line 244 of file datetime.cpp.
References calcSecFractions(), 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 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020 |