Skip to content

Commit

Permalink
Check for negative time in rclcpp::Time(int64_t nanoseconds, ...) con…
Browse files Browse the repository at this point in the history
…structor (#2510)

Signed-off-by: Nursharmin Ramli <[email protected]>
  • Loading branch information
sharminramli authored Apr 23, 2024
1 parent 5593961 commit de666d2
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 76 deletions.
1 change: 1 addition & 0 deletions rclcpp/include/rclcpp/time.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ class Time
/**
* \param nanoseconds since time epoch
* \param clock_type clock type
* \throws std::runtime_error if nanoseconds are negative
*/
RCLCPP_PUBLIC
explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);
Expand Down
10 changes: 10 additions & 0 deletions rclcpp/src/rclcpp/time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,10 @@ Time::Time(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type)
Time::Time(int64_t nanoseconds, rcl_clock_type_t clock_type)
: rcl_time_(init_time_point(clock_type))
{
if (nanoseconds < 0) {
throw std::runtime_error("cannot store a negative time point in rclcpp::Time");
}

rcl_time_.nanoseconds = nanoseconds;
}

Expand Down Expand Up @@ -249,6 +253,9 @@ Time::operator+=(const rclcpp::Duration & rhs)
}

rcl_time_.nanoseconds += rhs.nanoseconds();
if (rcl_time_.nanoseconds < 0) {
throw std::runtime_error("cannot store a negative time point in rclcpp::Time");
}

return *this;
}
Expand All @@ -264,6 +271,9 @@ Time::operator-=(const rclcpp::Duration & rhs)
}

rcl_time_.nanoseconds -= rhs.nanoseconds();
if (rcl_time_.nanoseconds < 0) {
throw std::runtime_error("cannot store a negative time point in rclcpp::Time");
}

return *this;
}
Expand Down
82 changes: 6 additions & 76 deletions rclcpp/test/rclcpp/test_time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,8 @@ TEST_F(TestTime, conversions) {

EXPECT_ANY_THROW(rclcpp::Time(-1, 1));

EXPECT_ANY_THROW(rclcpp::Time(-1));

EXPECT_ANY_THROW(
{
rclcpp::Time assignment(1, 2);
Expand Down Expand Up @@ -168,48 +170,6 @@ TEST_F(TestTime, conversions) {
EXPECT_EQ(time_msg.nanosec, HALF_SEC_IN_NS);
EXPECT_EQ(rclcpp::Time(time_msg).nanoseconds(), ONE_AND_HALF_SEC_IN_NS);
}

{
// Can rclcpp::Time be negative or not? The following constructor works:
rclcpp::Time time(-HALF_SEC_IN_NS);
auto time_msg = static_cast<builtin_interfaces::msg::Time>(time);
EXPECT_EQ(time_msg.sec, -1);
EXPECT_EQ(time_msg.nanosec, HALF_SEC_IN_NS);

// The opposite conversion throws...
EXPECT_ANY_THROW(
{
rclcpp::Time negative_time(time_msg);
});
}

{
// Can rclcpp::Time be negative or not? The following constructor works:
rclcpp::Time time(-ONE_SEC_IN_NS);
auto time_msg = static_cast<builtin_interfaces::msg::Time>(time);
EXPECT_EQ(time_msg.sec, -1);
EXPECT_EQ(time_msg.nanosec, 0u);

// The opposite conversion throws...
EXPECT_ANY_THROW(
{
rclcpp::Time negative_time(time_msg);
});
}

{
// Can rclcpp::Time be negative or not? The following constructor works:
rclcpp::Time time(-ONE_AND_HALF_SEC_IN_NS);
auto time_msg = static_cast<builtin_interfaces::msg::Time>(time);
EXPECT_EQ(time_msg.sec, -2);
EXPECT_EQ(time_msg.nanosec, HALF_SEC_IN_NS);

// The opposite conversion throws...
EXPECT_ANY_THROW(
{
rclcpp::Time negative_time(time_msg);
});
}
}

TEST_F(TestTime, operators) {
Expand Down Expand Up @@ -326,31 +286,18 @@ TEST_F(TestTime, overflow_detectors) {

TEST_F(TestTime, overflows) {
rclcpp::Time max_time(std::numeric_limits<rcl_time_point_value_t>::max());
rclcpp::Time min_time(std::numeric_limits<rcl_time_point_value_t>::min());
rclcpp::Duration one(1ns);
rclcpp::Duration two(2ns);

// Cross min/max
// Cross max
EXPECT_THROW(max_time + one, std::overflow_error);
EXPECT_THROW(min_time - one, std::underflow_error);
EXPECT_THROW(max_time - min_time, std::overflow_error);
EXPECT_THROW(min_time - max_time, std::underflow_error);
EXPECT_THROW(rclcpp::Time(max_time) += one, std::overflow_error);
EXPECT_THROW(rclcpp::Time(min_time) -= one, std::underflow_error);
EXPECT_NO_THROW(max_time - max_time);
EXPECT_NO_THROW(min_time - min_time);

// Cross zero in both directions
// Cross zero
rclcpp::Time one_time(1);
EXPECT_NO_THROW(one_time - two);
EXPECT_NO_THROW(rclcpp::Time(one_time) -= two);

rclcpp::Time minus_one_time(-1);
EXPECT_NO_THROW(minus_one_time + two);
EXPECT_NO_THROW(rclcpp::Time(minus_one_time) += two);

EXPECT_NO_THROW(one_time - minus_one_time);
EXPECT_NO_THROW(minus_one_time - one_time);
EXPECT_THROW(one_time - two, std::runtime_error);
EXPECT_THROW(rclcpp::Time(one_time) -= two, std::runtime_error);

rclcpp::Time two_time(2);
EXPECT_NO_THROW(one_time - two_time);
Expand Down Expand Up @@ -432,41 +379,24 @@ TEST_F(TestTime, test_overflow_underflow_throws) {
RCLCPP_EXPECT_THROW_EQ(
test_time = rclcpp::Time(INT64_MAX) + rclcpp::Duration(1ns),
std::overflow_error("addition leads to int64_t overflow"));
RCLCPP_EXPECT_THROW_EQ(
test_time = rclcpp::Time(INT64_MIN) + rclcpp::Duration(-1ns),
std::underflow_error("addition leads to int64_t underflow"));

RCLCPP_EXPECT_THROW_EQ(
test_time = rclcpp::Time(INT64_MAX) - rclcpp::Duration(-1ns),
std::overflow_error("time subtraction leads to int64_t overflow"));
RCLCPP_EXPECT_THROW_EQ(
test_time = rclcpp::Time(INT64_MIN) - rclcpp::Duration(1ns),
std::underflow_error("time subtraction leads to int64_t underflow"));

test_time = rclcpp::Time(INT64_MAX);
RCLCPP_EXPECT_THROW_EQ(
test_time += rclcpp::Duration(1ns),
std::overflow_error("addition leads to int64_t overflow"));
test_time = rclcpp::Time(INT64_MIN);
RCLCPP_EXPECT_THROW_EQ(
test_time += rclcpp::Duration(-1ns),
std::underflow_error("addition leads to int64_t underflow"));

test_time = rclcpp::Time(INT64_MAX);
RCLCPP_EXPECT_THROW_EQ(
test_time -= rclcpp::Duration(-1ns),
std::overflow_error("time subtraction leads to int64_t overflow"));
test_time = rclcpp::Time(INT64_MIN);
RCLCPP_EXPECT_THROW_EQ(
test_time -= rclcpp::Duration(1ns),
std::underflow_error("time subtraction leads to int64_t underflow"));

RCLCPP_EXPECT_THROW_EQ(
test_time = rclcpp::Duration::from_nanoseconds(INT64_MAX) + rclcpp::Time(1),
std::overflow_error("addition leads to int64_t overflow"));
RCLCPP_EXPECT_THROW_EQ(
test_time = rclcpp::Duration::from_nanoseconds(INT64_MIN) + rclcpp::Time(-1),
std::underflow_error("addition leads to int64_t underflow"));
}

class TestClockSleep : public ::testing::Test
Expand Down

0 comments on commit de666d2

Please sign in to comment.