Skip to content

Commit

Permalink
Move time functions into time.cpp.
Browse files Browse the repository at this point in the history
This should improve compile times for downstream projects.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Oct 18, 2021
1 parent 7006ceb commit 16562ce
Show file tree
Hide file tree
Showing 2 changed files with 52 additions and 36 deletions.
46 changes: 10 additions & 36 deletions tf2/include/tf2/time.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,46 +44,20 @@ using IDuration = std::chrono::duration<int, std::nano>;
// This is the zero time in ROS
static const TimePoint TimePointZero = TimePoint(IDuration::zero());

inline TimePoint get_now()
{
return std::chrono::system_clock::now();
}

inline Duration durationFromSec(double t_sec)
{
int32_t sec, nsec;
sec = static_cast<int32_t>(floor(t_sec));
nsec = static_cast<int32_t>(std::round((t_sec - sec) * 1e9));
// avoid rounding errors
sec += (nsec / 1000000000l);
nsec %= 1000000000l;
return std::chrono::seconds(sec) + std::chrono::nanoseconds(nsec);
}

inline TimePoint timeFromSec(double t_sec)
{
return tf2::TimePoint(durationFromSec(t_sec));
}
TF2_PUBLIC
TimePoint get_now();

inline double durationToSec(const tf2::Duration & input)
{
int64_t count = input.count();
TF2_PUBLIC
Duration durationFromSec(double t_sec);

// scale the nanoseconds separately for improved accuracy
int32_t sec, nsec;
nsec = static_cast<int32_t>(count % 1000000000l);
sec = static_cast<int32_t>((count - nsec) / 1000000000l);
TF2_PUBLIC
TimePoint timeFromSec(double t_sec);

double sec_double, nsec_double;
nsec_double = 1e-9 * static_cast<double>(nsec);
sec_double = static_cast<double>(sec);
return sec_double + nsec_double;
}
TF2_PUBLIC
double durationToSec(const tf2::Duration & input);

inline double timeToSec(const TimePoint & timepoint)
{
return durationToSec(Duration(timepoint.time_since_epoch()));
}
TF2_PUBLIC
double timeToSec(const TimePoint & timepoint);

TF2_PUBLIC
std::string displayTimePoint(const TimePoint & stamp);
Expand Down
42 changes: 42 additions & 0 deletions tf2/src/time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,55 @@

/** \author Tully Foote */

#include <chrono>
#include <stdexcept>
#include <string>

#include "rcutils/snprintf.h"
#include "rcutils/strerror.h"
#include "tf2/time.h"

tf2::TimePoint tf2::get_now()
{
return std::chrono::system_clock::now();
}

tf2::Duration tf2::durationFromSec(double t_sec)
{
int32_t sec, nsec;
sec = static_cast<int32_t>(floor(t_sec));
nsec = static_cast<int32_t>(std::round((t_sec - sec) * 1e9));
// avoid rounding errors
sec += (nsec / 1000000000l);
nsec %= 1000000000l;
return std::chrono::seconds(sec) + std::chrono::nanoseconds(nsec);
}

tf2::TimePoint tf2::timeFromSec(double t_sec)
{
return tf2::TimePoint(durationFromSec(t_sec));
}

double tf2::durationToSec(const tf2::Duration & input)
{
int64_t count = input.count();

// scale the nanoseconds separately for improved accuracy
int32_t sec, nsec;
nsec = static_cast<int32_t>(count % 1000000000l);
sec = static_cast<int32_t>((count - nsec) / 1000000000l);

double sec_double, nsec_double;
nsec_double = 1e-9 * static_cast<double>(nsec);
sec_double = static_cast<double>(sec);
return sec_double + nsec_double;
}

double tf2::timeToSec(const tf2::TimePoint & timepoint)
{
return durationToSec(tf2::Duration(timepoint.time_since_epoch()));
}

std::string tf2::displayTimePoint(const tf2::TimePoint & stamp)
{
const char * format_str = "%.6f";
Expand Down

0 comments on commit 16562ce

Please sign in to comment.