From d53dc11c226745811c997c1e21df34b7523a14d5 Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Thu, 14 Dec 2023 23:48:25 -0800 Subject: [PATCH] Bugfix for incorrect playback rate changes when pressing buttons (#1513) - Playback rate expected to be changed by 10% with each increase/decrease step. - Use +0.1 and -0.1 in decrease/increase rate formula instead of multiply by factor of the 1.1 and 0.9 respectively. Signed-off-by: Michael Orlov (cherry picked from commit 95f78b63f8cebc8c4a902b4783e4e7a1d0271d02) # Conflicts: # rosbag2_transport/src/rosbag2_transport/player.cpp --- rosbag2_transport/src/rosbag2_transport/player.cpp | 8 ++++++++ .../test/rosbag2_transport/test_keyboard_controls.cpp | 10 ++++++++-- 2 files changed, 16 insertions(+), 2 deletions(-) diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index c982d6603f..3b9021e8ee 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -637,12 +637,20 @@ void Player::add_keyboard_callbacks() ); add_key_callback( play_options_.increase_rate_key, +<<<<<<< HEAD [this]() {set_rate(get_rate() * 1.1);}, +======= + [this]() {owner_->set_rate(get_rate() + 0.1);}, +>>>>>>> 95f78b6 (Bugfix for incorrect playback rate changes when pressing buttons (#1513)) "Increase Rate 10%" ); add_key_callback( play_options_.decrease_rate_key, +<<<<<<< HEAD [this]() {set_rate(get_rate() * 0.9);}, +======= + [this]() {owner_->set_rate(get_rate() - 0.1);}, +>>>>>>> 95f78b6 (Bugfix for incorrect playback rate changes when pressing buttons (#1513)) "Decrease Rate 10%" ); } diff --git a/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp b/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp index a08e96ea49..fbb396db93 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp @@ -157,8 +157,14 @@ TEST_F(RosBag2PlayTestFixture, test_keyboard_controls) keyboard_handler->simulate_key_press(play_options_.pause_resume_toggle_key); EXPECT_THAT(player->is_paused(), true); - keyboard_handler->simulate_key_press(play_options_.increase_rate_key); + EXPECT_DOUBLE_EQ(player->get_rate(), 1.0); keyboard_handler->simulate_key_press(play_options_.decrease_rate_key); + // Each increase/decrease shall change playback rate value by 10% + EXPECT_DOUBLE_EQ(player->get_rate(), 0.9); + keyboard_handler->simulate_key_press(play_options_.increase_rate_key); + EXPECT_DOUBLE_EQ(player->get_rate(), 1.0); + keyboard_handler->simulate_key_press(play_options_.increase_rate_key); + EXPECT_DOUBLE_EQ(player->get_rate(), 1.1); // start play thread std::thread player_thread = std::thread([player]() {player->play();}); @@ -177,7 +183,7 @@ TEST_F(RosBag2PlayTestFixture, test_keyboard_controls) EXPECT_THAT(player->num_paused, 1); EXPECT_THAT(player->num_resumed, 1); EXPECT_THAT(player->num_played_next, 1); - EXPECT_THAT(player->num_set_rate, 2); + EXPECT_THAT(player->num_set_rate, 3); } TEST_F(RecordIntegrationTestFixture, test_keyboard_controls)