diff --git a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp index 046011ccc0..3577820ee8 100644 --- a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp +++ b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp @@ -124,7 +124,7 @@ PlayOptions get_play_options_from_node_params(rclcpp::Node & node) auto desc_rate = param_utils::float_param_description( "Playback rate (hz)", 0.000001, - std::numeric_limits::max()); + static_cast(std::numeric_limits::max())); play_options.rate = static_cast(node.declare_parameter("play.rate", 1.0, desc_rate)); diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp index a97b33801e..d7a16a1a99 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp @@ -151,7 +151,7 @@ TEST_P(ComposablePlayerTests, player_can_parse_parameters_from_file) { std::vector clock_trigger_topics {"/triggers/clock"}; EXPECT_EQ(play_options.clock_trigger_topics, clock_trigger_topics); EXPECT_EQ(play_options.delay.nanoseconds(), 1); - EXPECT_FLOAT_EQ(play_options.playback_duration.seconds(), -1); + EXPECT_FLOAT_EQ(play_options.playback_duration.seconds(), -1.0); EXPECT_EQ(play_options.playback_until_timestamp, -2500000000LL); EXPECT_EQ(play_options.start_offset, 999999999); EXPECT_EQ(play_options.wait_acked_timeout, -999999999);