Skip to content

Commit

Permalink
Fix conversion of negative durations to messages (#1188)
Browse files Browse the repository at this point in the history
* Fix conversion from negative Duration or Time to the respective message type and throw in Duration::to_rmw_time() if the duration is negative.
rmw_time_t cannot represent negative durations.

Constructors and assignment operators can be just defaulted.

Other changes are mainly cosmetical, to make conversions between signed
and unsigned types and between 32-bit and 64-bit types more explicit.

Signed-off-by: Johannes Meyer <[email protected]>

* Add -Wconversion compiler option and fix implicit conversions that might alter the value

Signed-off-by: Johannes Meyer <[email protected]>

* Fix usage of fixture class in some unit tests by using gtest macro TEST_F() instead of TEST().

Signed-off-by: Johannes Meyer <[email protected]>

* Add compiler option -Wno-sign-conversion to fix build with Clang on macOS

Signed-off-by: Johannes Meyer <[email protected]>
  • Loading branch information
meyerj authored and ivanpauno committed Jul 20, 2020
1 parent 342f225 commit fbd0e5a
Show file tree
Hide file tree
Showing 11 changed files with 294 additions and 96 deletions.
6 changes: 5 additions & 1 deletion rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,11 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
# About -Wno-sign-conversion: With Clang, -Wconversion implies -Wsign-conversion. There are a number of
# implicit sign conversions in rclcpp and gtest.cc, see https://ci.ros2.org/job/ci_osx/9265/.
# Hence disabling -Wsign-conversion for now until all those have eventually been fixed.
# (from https://github.com/ros2/rclcpp/pull/1188#issuecomment-650229140)
add_compile_options(-Wall -Wextra -Wconversion -Wno-sign-conversion -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual)
endif()

include_directories(include)
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/duration.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class RCLCPP_PUBLIC Duration
operator=(const Duration & rhs);

Duration &
operator=(const builtin_interfaces::msg::Duration & Duration_msg);
operator=(const builtin_interfaces::msg::Duration & duration_msg);

bool
operator==(const rclcpp::Duration & rhs) const;
Expand Down
14 changes: 10 additions & 4 deletions rclcpp/include/rclcpp/time.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,24 +37,24 @@ class Time
/// Time constructor
/**
* \param nanoseconds since time epoch
* \param clock clock type
* \param clock_type clock type
*/
RCLCPP_PUBLIC
explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock = RCL_SYSTEM_TIME);
explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);

RCLCPP_PUBLIC
Time(const Time & rhs);

/// Time constructor
/**
* \param time_msg builtin_interfaces time message to copy
* \param ros_time clock type
* \param clock_type clock type
* \throws std::runtime_error if seconds are negative
*/
RCLCPP_PUBLIC
Time(
const builtin_interfaces::msg::Time & time_msg,
rcl_clock_type_t ros_time = RCL_ROS_TIME);
rcl_clock_type_t clock_type = RCL_ROS_TIME);

/// Time constructor
/**
Expand All @@ -73,6 +73,12 @@ class Time
Time &
operator=(const Time & rhs);

/**
* Assign Time from a builtin_interfaces::msg::Time instance.
* The clock_type will be reset to RCL_ROS_TIME.
* Equivalent to *this = Time(time_msg, RCL_ROS_TIME).
* \throws std::runtime_error if seconds are negative
*/
RCLCPP_PUBLIC
Time &
operator=(const builtin_interfaces::msg::Time & time_msg);
Expand Down
35 changes: 19 additions & 16 deletions rclcpp/src/rclcpp/duration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,16 +47,14 @@ Duration::Duration(std::chrono::nanoseconds nanoseconds)
rcl_duration_.nanoseconds = nanoseconds.count();
}

Duration::Duration(const Duration & rhs)
{
rcl_duration_.nanoseconds = rhs.rcl_duration_.nanoseconds;
}
Duration::Duration(const Duration & rhs) = default;

Duration::Duration(
const builtin_interfaces::msg::Duration & duration_msg)
{
rcl_duration_.nanoseconds = RCL_S_TO_NS(static_cast<uint64_t>(duration_msg.sec));
rcl_duration_.nanoseconds += duration_msg.nanosec;
rcl_duration_.nanoseconds =
RCL_S_TO_NS(static_cast<rcl_duration_value_t>(duration_msg.sec));
rcl_duration_.nanoseconds += static_cast<rcl_duration_value_t>(duration_msg.nanosec);
}

Duration::Duration(const rcl_duration_t & duration)
Expand All @@ -68,24 +66,25 @@ Duration::Duration(const rcl_duration_t & duration)
Duration::operator builtin_interfaces::msg::Duration() const
{
builtin_interfaces::msg::Duration msg_duration;
msg_duration.sec = static_cast<std::int32_t>(RCL_NS_TO_S(rcl_duration_.nanoseconds));
msg_duration.nanosec =
static_cast<std::uint32_t>(rcl_duration_.nanoseconds % (1000 * 1000 * 1000));
constexpr rcl_duration_value_t kDivisor = RCL_S_TO_NS(1);
const auto result = std::div(rcl_duration_.nanoseconds, kDivisor);
if (result.rem >= 0) {
msg_duration.sec = static_cast<std::int32_t>(result.quot);
msg_duration.nanosec = static_cast<std::uint32_t>(result.rem);
} else {
msg_duration.sec = static_cast<std::int32_t>(result.quot - 1);
msg_duration.nanosec = static_cast<std::uint32_t>(kDivisor + result.rem);
}
return msg_duration;
}

Duration &
Duration::operator=(const Duration & rhs)
{
rcl_duration_.nanoseconds = rhs.rcl_duration_.nanoseconds;
return *this;
}
Duration::operator=(const Duration & rhs) = default;

Duration &
Duration::operator=(const builtin_interfaces::msg::Duration & duration_msg)
{
rcl_duration_.nanoseconds = RCL_S_TO_NS(static_cast<int64_t>(duration_msg.sec));
rcl_duration_.nanoseconds += duration_msg.nanosec;
*this = Duration(duration_msg);
return *this;
}

Expand Down Expand Up @@ -225,6 +224,10 @@ Duration::seconds() const
rmw_time_t
Duration::to_rmw_time() const
{
if (rcl_duration_.nanoseconds < 0) {
throw std::runtime_error("rmw_time_t cannot be negative");
}

// reuse conversion logic from msg creation
builtin_interfaces::msg::Duration msg = *this;
rmw_time_t result;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ __lockless_has_parameter(
// see https://en.cppreference.com/w/cpp/types/numeric_limits/epsilon
RCLCPP_LOCAL
bool
__are_doubles_equal(double x, double y, size_t ulp = 100)
__are_doubles_equal(double x, double y, double ulp = 100.0)
{
return std::abs(x - y) <= std::numeric_limits<double>::epsilon() * std::abs(x + y) * ulp;
}
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -298,7 +298,7 @@ NodeOptions::get_domain_id_from_env() const
_dupenv_s(&ros_domain_id, &ros_domain_id_size, env_var);
#endif
if (ros_domain_id) {
uint32_t number = strtoul(ros_domain_id, NULL, 0);
uint32_t number = static_cast<uint32_t>(strtoul(ros_domain_id, NULL, 0));
if (number == (std::numeric_limits<uint32_t>::max)()) {
#ifdef _WIN32
// free the ros_domain_id before throwing, if getenv was used on Windows
Expand Down
38 changes: 14 additions & 24 deletions rclcpp/src/rclcpp/time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,17 +62,13 @@ Time::Time(int64_t nanoseconds, rcl_clock_type_t clock_type)
rcl_time_.nanoseconds = nanoseconds;
}

Time::Time(const Time & rhs)
: rcl_time_(rhs.rcl_time_)
{
rcl_time_.nanoseconds = rhs.rcl_time_.nanoseconds;
}
Time::Time(const Time & rhs) = default;

Time::Time(
const builtin_interfaces::msg::Time & time_msg,
rcl_clock_type_t ros_time)
rcl_clock_type_t clock_type)
: rcl_time_(init_time_point(clock_type))
{
rcl_time_ = init_time_point(ros_time);
if (time_msg.sec < 0) {
throw std::runtime_error("cannot store a negative time point in rclcpp::Time");
}
Expand All @@ -94,31 +90,25 @@ Time::~Time()
Time::operator builtin_interfaces::msg::Time() const
{
builtin_interfaces::msg::Time msg_time;
msg_time.sec = static_cast<std::int32_t>(RCL_NS_TO_S(rcl_time_.nanoseconds));
msg_time.nanosec = static_cast<std::uint32_t>(rcl_time_.nanoseconds % (1000 * 1000 * 1000));
constexpr rcl_time_point_value_t kRemainder = RCL_S_TO_NS(1);
const auto result = std::div(rcl_time_.nanoseconds, kRemainder);
if (result.rem >= 0) {
msg_time.sec = static_cast<std::int32_t>(result.quot);
msg_time.nanosec = static_cast<std::uint32_t>(result.rem);
} else {
msg_time.sec = static_cast<std::int32_t>(result.quot - 1);
msg_time.nanosec = static_cast<std::uint32_t>(kRemainder + result.rem);
}
return msg_time;
}

Time &
Time::operator=(const Time & rhs)
{
rcl_time_ = rhs.rcl_time_;
return *this;
}
Time::operator=(const Time & rhs) = default;

Time &
Time::operator=(const builtin_interfaces::msg::Time & time_msg)
{
if (time_msg.sec < 0) {
throw std::runtime_error("cannot store a negative time point in rclcpp::Time");
}


rcl_clock_type_t ros_time = RCL_ROS_TIME;
rcl_time_ = init_time_point(ros_time); // TODO(tfoote) hard coded ROS here

rcl_time_.nanoseconds = RCL_S_TO_NS(static_cast<int64_t>(time_msg.sec));
rcl_time_.nanoseconds += time_msg.nanosec;
*this = Time(time_msg);
return *this;
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/executors/test_multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ TEST_F(TestMultiThreadedExecutor, timer_over_take) {

{
std::lock_guard<std::mutex> lock(last_mutex);
double diff = std::abs((now - last).nanoseconds()) / 1.0e9;
double diff = static_cast<double>(std::abs((now - last).nanoseconds())) / 1.0e9;
last = now;

if (diff < PERIOD - TOLERANCE || diff > PERIOD + TOLERANCE) {
Expand Down
118 changes: 109 additions & 9 deletions rclcpp/test/test_duration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,7 @@ class TestDuration : public ::testing::Test
{
};

// TEST(TestDuration, conversions) {
// TODO(tfoote) Implement conversion methods
// }

TEST(TestDuration, operators) {
TEST_F(TestDuration, operators) {
rclcpp::Duration old(1, 0);
rclcpp::Duration young(2, 0);

Expand Down Expand Up @@ -67,7 +63,7 @@ TEST(TestDuration, operators) {
EXPECT_TRUE(time == assignment_op_duration);
}

TEST(TestDuration, chrono_overloads) {
TEST_F(TestDuration, chrono_overloads) {
int64_t ns = 123456789l;
auto chrono_ns = std::chrono::nanoseconds(ns);
auto d1 = rclcpp::Duration(ns);
Expand All @@ -86,7 +82,7 @@ TEST(TestDuration, chrono_overloads) {
EXPECT_EQ(chrono_float_seconds, d5.to_chrono<decltype(chrono_float_seconds)>());
}

TEST(TestDuration, overflows) {
TEST_F(TestDuration, overflows) {
rclcpp::Duration max(std::numeric_limits<rcl_duration_value_t>::max());
rclcpp::Duration min(std::numeric_limits<rcl_duration_value_t>::min());

Expand All @@ -107,7 +103,7 @@ TEST(TestDuration, overflows) {
EXPECT_THROW(base_d_neg * 4, std::underflow_error);
}

TEST(TestDuration, negative_duration) {
TEST_F(TestDuration, negative_duration) {
rclcpp::Duration assignable_duration = rclcpp::Duration(0) - rclcpp::Duration(5, 0);

{
Expand All @@ -130,9 +126,113 @@ TEST(TestDuration, negative_duration) {
}
}

TEST(TestDuration, maximum_duration) {
TEST_F(TestDuration, maximum_duration) {
rclcpp::Duration max_duration = rclcpp::Duration::max();
rclcpp::Duration max(std::numeric_limits<int32_t>::max(), 999999999);

EXPECT_EQ(max_duration, max);
}

static const int64_t HALF_SEC_IN_NS = 500 * 1000 * 1000;
static const int64_t ONE_SEC_IN_NS = 1000 * 1000 * 1000;
static const int64_t ONE_AND_HALF_SEC_IN_NS = 3 * HALF_SEC_IN_NS;

TEST_F(TestDuration, from_seconds) {
EXPECT_EQ(rclcpp::Duration(0), rclcpp::Duration::from_seconds(0.0));
EXPECT_EQ(rclcpp::Duration(0), rclcpp::Duration::from_seconds(0));
EXPECT_EQ(rclcpp::Duration(1, HALF_SEC_IN_NS), rclcpp::Duration::from_seconds(1.5));
EXPECT_EQ(rclcpp::Duration(-ONE_AND_HALF_SEC_IN_NS), rclcpp::Duration::from_seconds(-1.5));
}

TEST_F(TestDuration, std_chrono_constructors) {
EXPECT_EQ(rclcpp::Duration(0), rclcpp::Duration(0.0s));
EXPECT_EQ(rclcpp::Duration(0), rclcpp::Duration(0s));
EXPECT_EQ(rclcpp::Duration(1, HALF_SEC_IN_NS), rclcpp::Duration(1.5s));
EXPECT_EQ(rclcpp::Duration(-1, 0), rclcpp::Duration(-1s));
}

TEST_F(TestDuration, conversions) {
{
const rclcpp::Duration duration(HALF_SEC_IN_NS);
const auto duration_msg = static_cast<builtin_interfaces::msg::Duration>(duration);
EXPECT_EQ(duration_msg.sec, 0);
EXPECT_EQ(duration_msg.nanosec, HALF_SEC_IN_NS);
EXPECT_EQ(rclcpp::Duration(duration_msg).nanoseconds(), HALF_SEC_IN_NS);

const auto rmw_time = duration.to_rmw_time();
EXPECT_EQ(rmw_time.sec, 0u);
EXPECT_EQ(rmw_time.nsec, static_cast<uint64_t>(HALF_SEC_IN_NS));

const auto chrono_duration = duration.to_chrono<std::chrono::nanoseconds>();
EXPECT_EQ(chrono_duration.count(), HALF_SEC_IN_NS);
}

{
const rclcpp::Duration duration(ONE_SEC_IN_NS);
const auto duration_msg = static_cast<builtin_interfaces::msg::Duration>(duration);
EXPECT_EQ(duration_msg.sec, 1);
EXPECT_EQ(duration_msg.nanosec, 0u);
EXPECT_EQ(rclcpp::Duration(duration_msg).nanoseconds(), ONE_SEC_IN_NS);

const auto rmw_time = duration.to_rmw_time();
EXPECT_EQ(rmw_time.sec, 1u);
EXPECT_EQ(rmw_time.nsec, 0u);

const auto chrono_duration = duration.to_chrono<std::chrono::nanoseconds>();
EXPECT_EQ(chrono_duration.count(), ONE_SEC_IN_NS);
}

{
const rclcpp::Duration duration(ONE_AND_HALF_SEC_IN_NS);
auto duration_msg = static_cast<builtin_interfaces::msg::Duration>(duration);
EXPECT_EQ(duration_msg.sec, 1);
EXPECT_EQ(duration_msg.nanosec, HALF_SEC_IN_NS);
EXPECT_EQ(rclcpp::Duration(duration_msg).nanoseconds(), ONE_AND_HALF_SEC_IN_NS);

auto rmw_time = duration.to_rmw_time();
EXPECT_EQ(rmw_time.sec, 1u);
EXPECT_EQ(rmw_time.nsec, static_cast<uint64_t>(HALF_SEC_IN_NS));

auto chrono_duration = duration.to_chrono<std::chrono::nanoseconds>();
EXPECT_EQ(chrono_duration.count(), ONE_AND_HALF_SEC_IN_NS);
}

{
rclcpp::Duration duration(-HALF_SEC_IN_NS);
auto duration_msg = static_cast<builtin_interfaces::msg::Duration>(duration);
EXPECT_EQ(duration_msg.sec, -1);
EXPECT_EQ(duration_msg.nanosec, HALF_SEC_IN_NS);
EXPECT_EQ(rclcpp::Duration(duration_msg).nanoseconds(), -HALF_SEC_IN_NS);

EXPECT_THROW(duration.to_rmw_time(), std::runtime_error);

auto chrono_duration = duration.to_chrono<std::chrono::nanoseconds>();
EXPECT_EQ(chrono_duration.count(), -HALF_SEC_IN_NS);
}

{
rclcpp::Duration duration(-ONE_SEC_IN_NS);
auto duration_msg = static_cast<builtin_interfaces::msg::Duration>(duration);
EXPECT_EQ(duration_msg.sec, -1);
EXPECT_EQ(duration_msg.nanosec, 0u);
EXPECT_EQ(rclcpp::Duration(duration_msg).nanoseconds(), -ONE_SEC_IN_NS);

EXPECT_THROW(duration.to_rmw_time(), std::runtime_error);

auto chrono_duration = duration.to_chrono<std::chrono::nanoseconds>();
EXPECT_EQ(chrono_duration.count(), -ONE_SEC_IN_NS);
}

{
rclcpp::Duration duration(-ONE_AND_HALF_SEC_IN_NS);
auto duration_msg = static_cast<builtin_interfaces::msg::Duration>(duration);
EXPECT_EQ(duration_msg.sec, -2);
EXPECT_EQ(duration_msg.nanosec, HALF_SEC_IN_NS);
EXPECT_EQ(rclcpp::Duration(duration_msg).nanoseconds(), -ONE_AND_HALF_SEC_IN_NS);

EXPECT_THROW(duration.to_rmw_time(), std::runtime_error);

auto chrono_duration = duration.to_chrono<std::chrono::nanoseconds>();
EXPECT_EQ(chrono_duration.count(), -ONE_AND_HALF_SEC_IN_NS);
}
}
Loading

0 comments on commit fbd0e5a

Please sign in to comment.