Skip to content

Commit

Permalink
Add recorder keyboard control test
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
  • Loading branch information
ivanpauno committed Nov 11, 2021
1 parent a1a1d4a commit b6c35a6
Show file tree
Hide file tree
Showing 2 changed files with 31 additions and 1 deletion.
3 changes: 2 additions & 1 deletion rosbag2_transport/include/rosbag2_transport/recorder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,8 @@ class Recorder : public rclcpp::Node
ROSBAG2_TRANSPORT_PUBLIC
bool is_paused();

inline constexpr static const auto kPauseResumeToggleKey = KeyboardHandler::KeyCode::SPACE;

private:
void topics_discovery();

Expand Down Expand Up @@ -157,7 +159,6 @@ class Recorder : public rclcpp::Node
// Toogle paused key callback handle
KeyboardHandler::callback_handle_t toggle_paused_key_callback_handle_ =
KeyboardHandler::invalid_handle;
inline constexpr static const auto kPauseResumeToggleKey = KeyboardHandler::KeyCode::SPACE;
};

} // namespace rosbag2_transport
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,13 @@
#include "rosbag2_test_common/subscription_manager.hpp"

#include "rosbag2_transport/player.hpp"
#include "rosbag2_transport/recorder.hpp"

#include "test_msgs/msg/arrays.hpp"
#include "test_msgs/msg/basic_types.hpp"
#include "test_msgs/message_fixtures.hpp"

#include "record_integration_fixture.hpp"
#include "rosbag2_play_test_fixture.hpp"
#include "rosbag2_transport_test_fixture.hpp"
#include "mock_keyboard_handler.hpp"
Expand Down Expand Up @@ -177,3 +179,30 @@ TEST_F(RosBag2PlayTestFixture, test_keyboard_controls)
EXPECT_THAT(player->num_played_next, 1);
EXPECT_THAT(player->num_set_rate, 2);
}

TEST_F(RecordIntegrationTestFixture, test_keyboard_controls)
{
auto mock_sequential_writer = std::make_unique<MockSequentialWriter>();
auto writer = std::make_unique<rosbag2_cpp::Writer>(std::move(mock_sequential_writer));
auto keyboard_handler = std::make_shared<MockKeyboardHandler>();

rosbag2_transport::RecordOptions record_options = {true, false, {}, "rmw_format", 100ms};
record_options.start_paused = true;

// play bag in thread

This comment has been minimized.

Copy link
@MichaelOrlov

MichaelOrlov Nov 16, 2021

Contributor

It seems wrong comment. Did you mean "record bag in thread" instead?

This comment has been minimized.

Copy link
@ivanpauno

ivanpauno Nov 17, 2021

Author Member

I copy-pasted the comment from test_keyboard_controls.
I will delete it as it's not really helpful.

This comment has been minimized.

Copy link
@ivanpauno

ivanpauno Nov 17, 2021

Author Member

Fixed in bca8e74

This comment has been minimized.

Copy link
@MichaelOrlov

MichaelOrlov Nov 17, 2021

Contributor

Thanks

auto recorder = std::make_shared<Recorder>(
std::move(writer), keyboard_handler, storage_options_,
record_options, "test_count_recorder");

recorder->record();

this->start_async_spin(recorder);

EXPECT_THAT(recorder->is_paused(), true);
keyboard_handler->simulate_key_press(rosbag2_transport::Recorder::kPauseResumeToggleKey);
EXPECT_THAT(recorder->is_paused(), false);
keyboard_handler->simulate_key_press(rosbag2_transport::Recorder::kPauseResumeToggleKey);
EXPECT_THAT(recorder->is_paused(), true);

this->stop_spinning();
}

0 comments on commit b6c35a6

Please sign in to comment.