@@ -363,10 +363,27 @@ TEST_F(TestTime, seconds) {
363363}
364364
365365TEST_F (TestTime, test_max) {
366- const rclcpp::Time time_max = rclcpp::Time::max ();
367- const rclcpp::Time max_time (std::numeric_limits<int32_t >::max (), 999999999 );
368- EXPECT_DOUBLE_EQ (max_time.seconds (), time_max.seconds ());
369- EXPECT_EQ (max_time.nanoseconds (), time_max.nanoseconds ());
366+ // Same clock types
367+ for (rcl_clock_type_t type = RCL_ROS_TIME;
368+ type != RCL_STEADY_TIME; type = static_cast <rcl_clock_type_t >(type + 1 ))
369+ {
370+ const rclcpp::Time time_max = rclcpp::Time::max (type);
371+ const rclcpp::Time max_time (std::numeric_limits<int32_t >::max (), 999999999 , type);
372+ EXPECT_DOUBLE_EQ (max_time.seconds (), time_max.seconds ());
373+ EXPECT_EQ (max_time.nanoseconds (), time_max.nanoseconds ());
374+ }
375+ // Different clock types
376+ {
377+ const rclcpp::Time time_max = rclcpp::Time::max (RCL_ROS_TIME);
378+ const rclcpp::Time max_time (std::numeric_limits<int32_t >::max (), 999999999 , RCL_STEADY_TIME);
379+ EXPECT_ANY_THROW ((void )(time_max == max_time));
380+ EXPECT_ANY_THROW ((void )(time_max != max_time));
381+ EXPECT_ANY_THROW ((void )(time_max <= max_time));
382+ EXPECT_ANY_THROW ((void )(time_max >= max_time));
383+ EXPECT_ANY_THROW ((void )(time_max < max_time));
384+ EXPECT_ANY_THROW ((void )(time_max > max_time));
385+ EXPECT_ANY_THROW ((void )(time_max - max_time));
386+ }
370387}
371388
372389TEST_F (TestTime, test_constructor_from_rcl_time_point) {
0 commit comments