Skip to content

Commit

Permalink
Rule of five: implement move operators
Browse files Browse the repository at this point in the history
Signed-off-by: Tim Clephas <tim.clephas@nobleo.nl>
  • Loading branch information
Timple committed Feb 27, 2024
1 parent 091f29f commit 533ea23
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 3 deletions.
12 changes: 12 additions & 0 deletions rclcpp/include/rclcpp/time.hpp
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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
*/
Expand Down
9 changes: 6 additions & 3 deletions rclcpp/src/rclcpp/time.cpp
Expand Up @@ -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)
Expand All @@ -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
{
Expand All @@ -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
{
Expand Down

0 comments on commit 533ea23

Please sign in to comment.