@@ -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+
82111TEST_F (TestDuration, chrono_overloads) {
83112 int64_t ns = 123456789l ;
84113 auto chrono_ns = std::chrono::nanoseconds (ns);
0 commit comments