Skip to content

Commit

Permalink
Make TimeStamp obsolete
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Nov 4, 2022
1 parent 736e242 commit b42fd6a
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 121 deletions.
73 changes: 1 addition & 72 deletions fuse_core/include/fuse_core/time.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,78 +64,6 @@

namespace fuse_core
{
using Duration = std::chrono::nanoseconds; // rclcpp uses nanosecond durations

/**
* @brief Implements a Time class that supports interoperability between rclcpp and std::chrono time
*
* The class is implemented as a thin wrapper around rclcpp::Time. This allows us to take advantage
* of the operator overloads and clock type tracking of the parent class. Including the consistency
* checks for clock types when doing time arithmetic.
*
* To support this, the internal representation of time is an rclcpp::Time object and conversion
* functions and constructors are written to create this object out of primitive, rclcpp::Time and
* std::chrono time objects.
*
* A significant deviation from rclcpp:Time is the introduction of the default constructor that
* explicitly sets the clock type to RCL_CLOCK_UNINITIALIZED. This is done to differentiate between
* zero-initializations of time, and an uninitialized time.
*/
class TimeStamp : public rclcpp::Time
{
public:
// TODO(CH3): Write docstrings for these once interfaces have stabilized
TimeStamp();
TimeStamp(const TimeStamp& rhs);

TimeStamp(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type=RCL_SYSTEM_TIME);
TimeStamp(int64_t nanoseconds, rcl_clock_type_t clock_type=RCL_SYSTEM_TIME);

TimeStamp(const rclcpp::Time& time);
TimeStamp(std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds>& stamp);


rclcpp::Time to_ros() const;
std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds> to_chrono() const;

inline bool initialized() const {
return this->get_clock_type() != RCL_CLOCK_UNINITIALIZED;
}

inline std::chrono::nanoseconds time_since_epoch() const {
return std::chrono::nanoseconds(this->nanoseconds());
}


// OPERATORS ===================================================================================
TimeStamp & operator=(const TimeStamp & rhs) = default;

inline TimeStamp & operator=(const rclcpp::Time & time) {
*this = TimeStamp(time);
return *this;
}

inline TimeStamp & operator=(const builtin_interfaces::msg::Time & time_msg) {
*this = TimeStamp(time_msg);
return *this;
}

inline operator std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds>() const {
return this->to_chrono();
}
};


/**
* @brief provide an overload for use with the ostream << operator
*
* Present a human readable fuse_core::TimeStamp (in nanosecond units)
*
* @param[in] timestamp The rclcpp::Time to convert to print
*/
std::ostream& operator<<(std::ostream& os, const fuse_core::TimeStamp& timestamp);


/**
* @brief Check if clock's time is valid (non-zero)
*
Expand Down Expand Up @@ -180,6 +108,7 @@ bool wait_for_valid(
const rclcpp::Duration & timeout,
rclcpp::Context::SharedPtr context = rclcpp::contexts::get_global_default_context(),
const rclcpp::Duration & wait_tick_ns = rclcpp::Duration(0, static_cast<uint32_t>(1e7)));

}

#endif // FUSE_CORE_TIME_H
49 changes: 0 additions & 49 deletions fuse_core/src/time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,57 +51,8 @@
#include "rcl/time.h"
#include <rclcpp/utilities.hpp>

using chrono_ns_time_point_t =
std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds>;

namespace fuse_core
{
TimeStamp::TimeStamp() :
rclcpp::Time(static_cast<int64_t>(0), RCL_CLOCK_UNINITIALIZED)
{}

TimeStamp::TimeStamp(const TimeStamp& rhs) = default;

TimeStamp::TimeStamp(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type) :
rclcpp::Time(seconds, nanoseconds, clock_type)
{}

TimeStamp::TimeStamp(int64_t nanoseconds, rcl_clock_type_t clock_type) :
rclcpp::Time(nanoseconds, clock_type)
{}

TimeStamp::TimeStamp(const rclcpp::Time& time) :
rclcpp::Time(time)
{}

TimeStamp::TimeStamp(chrono_ns_time_point_t& stamp):
rclcpp::Time(stamp.time_since_epoch().count(), RCL_SYSTEM_TIME)
{}

rclcpp::Time TimeStamp::to_ros() const
{
return rclcpp::Time(this->nanoseconds(), this->get_clock_type());
}

chrono_ns_time_point_t TimeStamp::to_chrono() const
{
if (this->get_clock_type() != RCL_SYSTEM_TIME) {
throw std::runtime_error("Constructing system clock time_point from non-system clock");
}
return chrono_ns_time_point_t(
std::chrono::nanoseconds(this->nanoseconds())
);
}


// UTILITIES =======================================================================================
std::ostream& operator<<(std::ostream& os, const fuse_core::TimeStamp& timestamp)
{
os << timestamp.nanoseconds();
return os;
}


bool is_valid(rclcpp::Clock::SharedPtr clock, rclcpp::Context::SharedPtr context)
{
// Checks for null pointer, missing get_now() implementation, and RCL_CLOCK_UNINITIALIZED
Expand Down

0 comments on commit b42fd6a

Please sign in to comment.