@@ -79,6 +79,37 @@ 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; // 0.1s
84+ time_msg.sec = 0 ;
85+ time_msg.nanosec = 100000000 ;
86+ rclcpp::Duration pos_duration (1 , 100000000 ); // 1.1s
87+ rclcpp::Duration neg_duration (-2 , 900000000 ); // -1.1s
88+
89+ builtin_interfaces::msg::Time res_addpos = time_msg + pos_duration;
90+ EXPECT_EQ (res_addpos.sec , 1 );
91+ EXPECT_EQ (res_addpos.nanosec , 200000000 );
92+
93+ builtin_interfaces::msg::Time res_addneg = time_msg + neg_duration;
94+ EXPECT_EQ (res_addneg.sec , -1 );
95+ EXPECT_EQ (res_addneg.nanosec , 0 );
96+
97+ builtin_interfaces::msg::Time res_subpos = time_msg - pos_duration;
98+ EXPECT_EQ (res_subpos.sec , -1 );
99+ EXPECT_EQ (res_subpos.nanosec , 0 );
100+
101+ builtin_interfaces::msg::Time res_subneg = time_msg - neg_duration;
102+ EXPECT_EQ (res_subneg.sec , 1 );
103+ EXPECT_EQ (res_subneg.nanosec , 200000000 );
104+
105+ builtin_interfaces::msg::Time neg_time_msg;
106+ neg_time_msg.sec = -1 ;
107+ auto max = rclcpp::Duration::from_nanoseconds (std::numeric_limits<rcl_duration_value_t >::max ());
108+
109+ EXPECT_THROW (neg_time_msg + max, std::runtime_error);
110+ EXPECT_THROW (time_msg + max, std::overflow_error);
111+ }
112+
82113TEST_F (TestDuration, chrono_overloads) {
83114 int64_t ns = 123456789l ;
84115 auto chrono_ns = std::chrono::nanoseconds (ns);
0 commit comments