Skip to content

Commit 38bcda4

Browse files
authored
feat: add/minus for msg::Time and rclcpp::Duration (#2419)
* feat: add/minus for msg::Time and rclcpp::Duration Signed-off-by: HuaTsai <[email protected]>
1 parent c500695 commit 38bcda4

File tree

5 files changed

+111
-11
lines changed

5 files changed

+111
-11
lines changed

rclcpp/include/rclcpp/duration.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <chrono>
1919

2020
#include "builtin_interfaces/msg/duration.hpp"
21+
#include "builtin_interfaces/msg/time.hpp"
2122
#include "rcl/time.h"
2223
#include "rclcpp/visibility_control.hpp"
2324

@@ -158,6 +159,14 @@ class RCLCPP_PUBLIC Duration
158159
Duration() = default;
159160
};
160161

162+
RCLCPP_PUBLIC
163+
builtin_interfaces::msg::Time
164+
operator+(const builtin_interfaces::msg::Time & lhs, const rclcpp::Duration & rhs);
165+
166+
RCLCPP_PUBLIC
167+
builtin_interfaces::msg::Time
168+
operator-(const builtin_interfaces::msg::Time & lhs, const rclcpp::Duration & rhs);
169+
161170
} // namespace rclcpp
162171

163172
#endif // RCLCPP__DURATION_HPP_

rclcpp/include/rclcpp/time.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -222,6 +222,15 @@ RCLCPP_PUBLIC
222222
Time
223223
operator+(const rclcpp::Duration & lhs, const rclcpp::Time & rhs);
224224

225+
/// Convert rcl_time_point_value_t to builtin_interfaces::msg::Time
226+
/**
227+
* \param[in] time_point is a rcl_time_point_value_t
228+
* \return the builtin_interfaces::msg::Time from the time_point
229+
*/
230+
RCLCPP_PUBLIC
231+
builtin_interfaces::msg::Time
232+
convert_rcl_time_to_sec_nanos(const rcl_time_point_value_t & time_point);
233+
225234
} // namespace rclcpp
226235

227236
#endif // RCLCPP__TIME_HPP_

rclcpp/src/rclcpp/duration.cpp

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,8 @@
2828

2929
#include "rcutils/logging_macros.h"
3030

31+
#include "rclcpp/utilities.hpp"
32+
3133
namespace rclcpp
3234
{
3335

@@ -316,4 +318,50 @@ Duration::from_nanoseconds(rcl_duration_value_t nanoseconds)
316318
return ret;
317319
}
318320

321+
builtin_interfaces::msg::Time
322+
operator+(const builtin_interfaces::msg::Time & lhs, const rclcpp::Duration & rhs)
323+
{
324+
if (lhs.sec < 0) {
325+
throw std::runtime_error("message time is negative");
326+
}
327+
328+
rcl_time_point_value_t rcl_time;
329+
rcl_time = RCL_S_TO_NS(static_cast<int64_t>(lhs.sec));
330+
rcl_time += lhs.nanosec;
331+
332+
if (rclcpp::add_will_overflow(rcl_time, rhs.nanoseconds())) {
333+
throw std::overflow_error("addition leads to int64_t overflow");
334+
}
335+
if (rclcpp::add_will_underflow(rcl_time, rhs.nanoseconds())) {
336+
throw std::underflow_error("addition leads to int64_t underflow");
337+
}
338+
339+
rcl_time += rhs.nanoseconds();
340+
341+
return convert_rcl_time_to_sec_nanos(rcl_time);
342+
}
343+
344+
builtin_interfaces::msg::Time
345+
operator-(const builtin_interfaces::msg::Time & lhs, const rclcpp::Duration & rhs)
346+
{
347+
if (lhs.sec < 0) {
348+
throw std::runtime_error("message time is negative");
349+
}
350+
351+
rcl_time_point_value_t rcl_time;
352+
rcl_time = RCL_S_TO_NS(static_cast<int64_t>(lhs.sec));
353+
rcl_time += lhs.nanosec;
354+
355+
if (rclcpp::sub_will_overflow(rcl_time, rhs.nanoseconds())) {
356+
throw std::overflow_error("addition leads to int64_t overflow");
357+
}
358+
if (rclcpp::sub_will_underflow(rcl_time, rhs.nanoseconds())) {
359+
throw std::underflow_error("addition leads to int64_t underflow");
360+
}
361+
362+
rcl_time -= rhs.nanoseconds();
363+
364+
return convert_rcl_time_to_sec_nanos(rcl_time);
365+
}
366+
319367
} // namespace rclcpp

rclcpp/src/rclcpp/time.cpp

Lines changed: 16 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -90,17 +90,7 @@ Time::~Time()
9090

9191
Time::operator builtin_interfaces::msg::Time() const
9292
{
93-
builtin_interfaces::msg::Time msg_time;
94-
constexpr rcl_time_point_value_t kRemainder = RCL_S_TO_NS(1);
95-
const auto result = std::div(rcl_time_.nanoseconds, kRemainder);
96-
if (result.rem >= 0) {
97-
msg_time.sec = static_cast<std::int32_t>(result.quot);
98-
msg_time.nanosec = static_cast<std::uint32_t>(result.rem);
99-
} else {
100-
msg_time.sec = static_cast<std::int32_t>(result.quot - 1);
101-
msg_time.nanosec = static_cast<std::uint32_t>(kRemainder + result.rem);
102-
}
103-
return msg_time;
93+
return convert_rcl_time_to_sec_nanos(rcl_time_.nanoseconds);
10494
}
10595

10696
Time &
@@ -281,5 +271,20 @@ Time::max(rcl_clock_type_t clock_type)
281271
return Time(std::numeric_limits<int32_t>::max(), 999999999, clock_type);
282272
}
283273

274+
builtin_interfaces::msg::Time
275+
convert_rcl_time_to_sec_nanos(const rcl_time_point_value_t & time_point)
276+
{
277+
builtin_interfaces::msg::Time ret;
278+
constexpr rcl_time_point_value_t kRemainder = RCL_S_TO_NS(1);
279+
const auto result = std::div(time_point, kRemainder);
280+
if (result.rem >= 0) {
281+
ret.sec = static_cast<std::int32_t>(result.quot);
282+
ret.nanosec = static_cast<std::uint32_t>(result.rem);
283+
} else {
284+
ret.sec = static_cast<std::int32_t>(result.quot - 1);
285+
ret.nanosec = static_cast<std::uint32_t>(kRemainder + result.rem);
286+
}
287+
return ret;
288+
}
284289

285290
} // namespace rclcpp

rclcpp/test/rclcpp/test_duration.cpp

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,35 @@ TEST_F(TestDuration, operators) {
7979
EXPECT_TRUE(time == assignment_op_duration);
8080
}
8181

82+
TEST_F(TestDuration, operators_with_message_stamp) {
83+
builtin_interfaces::msg::Time time_msg = rclcpp::Time(0, 100000000u); // 0.1s
84+
rclcpp::Duration pos_duration(1, 100000000u); // 1.1s
85+
rclcpp::Duration neg_duration(-2, 900000000u); // -1.1s
86+
87+
builtin_interfaces::msg::Time res_addpos = time_msg + pos_duration;
88+
EXPECT_EQ(res_addpos.sec, 1);
89+
EXPECT_EQ(res_addpos.nanosec, 200000000u);
90+
91+
builtin_interfaces::msg::Time res_addneg = time_msg + neg_duration;
92+
EXPECT_EQ(res_addneg.sec, -1);
93+
EXPECT_EQ(res_addneg.nanosec, 0);
94+
95+
builtin_interfaces::msg::Time res_subpos = time_msg - pos_duration;
96+
EXPECT_EQ(res_subpos.sec, -1);
97+
EXPECT_EQ(res_subpos.nanosec, 0);
98+
99+
builtin_interfaces::msg::Time res_subneg = time_msg - neg_duration;
100+
EXPECT_EQ(res_subneg.sec, 1);
101+
EXPECT_EQ(res_subneg.nanosec, 200000000u);
102+
103+
builtin_interfaces::msg::Time neg_time_msg;
104+
neg_time_msg.sec = -1;
105+
auto max = rclcpp::Duration::from_nanoseconds(std::numeric_limits<rcl_duration_value_t>::max());
106+
107+
EXPECT_THROW(neg_time_msg + max, std::runtime_error);
108+
EXPECT_THROW(time_msg + max, std::overflow_error);
109+
}
110+
82111
TEST_F(TestDuration, chrono_overloads) {
83112
int64_t ns = 123456789l;
84113
auto chrono_ns = std::chrono::nanoseconds(ns);

0 commit comments

Comments
 (0)