File tree Expand file tree Collapse file tree 2 files changed +18
-3
lines changed Expand file tree Collapse file tree 2 files changed +18
-3
lines changed Original file line number Diff line number Diff line change @@ -57,6 +57,10 @@ class Time
5757 RCLCPP_PUBLIC
5858 Time (const Time & rhs);
5959
60+ // / Move constructor
61+ RCLCPP_PUBLIC
62+ Time (Time && rhs) noexcept ;
63+
6064 // / Time constructor
6165 /* *
6266 * \param time_msg builtin_interfaces time message to copy
@@ -84,6 +88,7 @@ class Time
8488 operator builtin_interfaces::msg::Time () const ;
8589
8690 /* *
91+ * Copy assignment operator
8792 * \throws std::runtime_error if seconds are negative
8893 */
8994 RCLCPP_PUBLIC
@@ -100,6 +105,13 @@ class Time
100105 Time &
101106 operator =(const builtin_interfaces::msg::Time & time_msg);
102107
108+ /* *
109+ * Move assignment operator
110+ */
111+ RCLCPP_PUBLIC
112+ Time &
113+ operator =(Time && rhs) noexcept ;
114+
103115 /* *
104116 * \throws std::runtime_error if the time sources are different
105117 */
Original file line number Diff line number Diff line change @@ -65,6 +65,8 @@ Time::Time(int64_t nanoseconds, rcl_clock_type_t clock_type)
6565
6666Time::Time (const Time & rhs) = default ;
6767
68+ Time::Time (Time && rhs) noexcept = default ;
69+
6870Time::Time (
6971 const builtin_interfaces::msg::Time & time_msg,
7072 rcl_clock_type_t clock_type)
@@ -84,9 +86,7 @@ Time::Time(const rcl_time_point_t & time_point)
8486 // noop
8587}
8688
87- Time::~Time ()
88- {
89- }
89+ Time::~Time () = default ;
9090
9191Time::operator builtin_interfaces::msg::Time () const
9292{
@@ -103,6 +103,9 @@ Time::operator=(const builtin_interfaces::msg::Time & time_msg)
103103 return *this ;
104104}
105105
106+ Time &
107+ Time::operator =(Time && rhs) noexcept = default ;
108+
106109bool
107110Time::operator ==(const rclcpp::Time & rhs) const
108111{
You can’t perform that action at this time.
0 commit comments