diff --git a/rclcpp/include/rclcpp/time.hpp b/rclcpp/include/rclcpp/time.hpp index 15e063d1d2..a931f3ac9c 100644 --- a/rclcpp/include/rclcpp/time.hpp +++ b/rclcpp/include/rclcpp/time.hpp @@ -57,6 +57,10 @@ class Time RCLCPP_PUBLIC Time(const Time & rhs); + /// Move constructor + RCLCPP_PUBLIC + Time(Time && rhs) noexcept; + /// Time constructor /** * \param time_msg builtin_interfaces time message to copy @@ -84,6 +88,7 @@ class Time operator builtin_interfaces::msg::Time() const; /** + * Copy assignment operator * \throws std::runtime_error if seconds are negative */ RCLCPP_PUBLIC @@ -100,6 +105,13 @@ class Time Time & operator=(const builtin_interfaces::msg::Time & time_msg); + /** + * Move assignment operator + */ + RCLCPP_PUBLIC + Time & + operator=(Time && rhs) noexcept; + /** * \throws std::runtime_error if the time sources are different */ diff --git a/rclcpp/src/rclcpp/time.cpp b/rclcpp/src/rclcpp/time.cpp index a0be141312..978651516c 100644 --- a/rclcpp/src/rclcpp/time.cpp +++ b/rclcpp/src/rclcpp/time.cpp @@ -65,6 +65,8 @@ Time::Time(int64_t nanoseconds, rcl_clock_type_t clock_type) Time::Time(const Time & rhs) = default; +Time::Time(Time && rhs) noexcept = default; + Time::Time( const builtin_interfaces::msg::Time & time_msg, rcl_clock_type_t clock_type) @@ -84,9 +86,7 @@ Time::Time(const rcl_time_point_t & time_point) // noop } -Time::~Time() -{ -} +Time::~Time() = default; Time::operator builtin_interfaces::msg::Time() const { @@ -103,6 +103,9 @@ Time::operator=(const builtin_interfaces::msg::Time & time_msg) return *this; } +Time & +Time::operator=(Time && rhs) noexcept = default; + bool Time::operator==(const rclcpp::Time & rhs) const {