Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add delay option #789

Merged
merged 11 commits into from
Jul 6, 2021
Merged
Show file tree
Hide file tree
Changes from 9 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions ros2bag/ros2bag/verb/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,9 @@ def add_arguments(self, parser, cli_name): # noqa: D102
'--clock', type=positive_float, nargs='?', const=40, default=0,
help='Publish to /clock at a specific frequency in Hz, to act as a ROS Time Source. '
'Value must be positive. Defaults to not publishing.')
parser.add_argument(
'-d', '--delay', type=float, default=0.0,
help='Sleep SEC seconds after play. Valid range > 0.0')

def main(self, *, args): # noqa: D102
qos_profile_overrides = {} # Specify a valid default
Expand Down Expand Up @@ -116,6 +119,7 @@ def main(self, *, args): # noqa: D102
play_options.loop = args.loop
play_options.topic_remapping_options = topic_remapping
play_options.clock_publish_frequency = args.clock
play_options.delay = args.delay

player = Player()
player.play(storage_options, play_options)
1 change: 1 addition & 0 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,6 +220,7 @@ PYBIND11_MODULE(_transport, m) {
.def_readwrite("loop", &PlayOptions::loop)
.def_readwrite("topic_remapping_options", &PlayOptions::topic_remapping_options)
.def_readwrite("clock_publish_frequency", &PlayOptions::clock_publish_frequency)
.def_readwrite("delay", &PlayOptions::delay)
;

py::class_<RecordOptions>(m, "RecordOptions")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@ struct PlayOptions
// Rate in Hz at which to publish to /clock.
// 0 (or negative) means that no publisher will be created
double clock_publish_frequency = 0.0;

zmichaels11 marked this conversation as resolved.
Show resolved Hide resolved
// Sleep SEC seconds after play. Valid range > 0.0.
MichaelOrlov marked this conversation as resolved.
Show resolved Hide resolved
float delay = 0.0;
};

} // namespace rosbag2_transport
Expand Down
17 changes: 17 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,8 +213,25 @@ bool Player::is_storage_completely_loaded() const
void Player::play()
{
is_in_play_ = true;

float delay;
if (play_options_.delay >= 0.0) {
delay = play_options_.delay;
} else {
RCLCPP_WARN(
this->get_logger(),
"Invalid delay value: %f. Delay is disabled.",
play_options_.delay);
delay = 0.0;
}

try {
do {
if (delay > 0.0) {
RCLCPP_INFO_STREAM(this->get_logger(), "Sleep " << delay << " sec");
std::chrono::duration<float> duration(delay);
std::this_thread::sleep_for(duration);
}
reader_->open(storage_options_, {"", rmw_get_serialization_format()});
const auto starting_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
reader_->get_metadata().starting_time.time_since_epoch()).count();
Expand Down
11 changes: 8 additions & 3 deletions rosbag2_transport/test/rosbag2_transport/test_play_loop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ TEST_F(RosBag2PlayTestFixture, play_bag_file_twice) {
const size_t read_ahead_queue_size = 1000;
const float rate = 1.0;
const bool loop_playback = false;
double clock_publish_frequency = 0.0;
const float delay = 1.0;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you also test for an invalid delay value?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I added tests for delay in dfee76a.


auto primitive_message1 = get_messages_basic_types()[0];
primitive_message1->int32_value = test_value;
Expand All @@ -64,8 +66,9 @@ TEST_F(RosBag2PlayTestFixture, play_bag_file_twice) {

auto await_received_messages = sub_->spin_subscriptions();

rosbag2_transport::PlayOptions play_options =
{read_ahead_queue_size, "", rate, {}, {}, loop_playback, {}};
rosbag2_transport::PlayOptions play_options = {
read_ahead_queue_size, "", rate, {}, {}, loop_playback, {},
clock_publish_frequency, delay};
auto player = std::make_shared<rosbag2_transport::Player>(
std::move(
reader), storage_options_, play_options);
Expand Down Expand Up @@ -100,6 +103,8 @@ TEST_F(RosBag2PlayTestFixture, messages_played_in_loop) {
const size_t read_ahead_queue_size = 1000;
const float rate = 1.0;
const bool loop_playback = true;
const double clock_publish_frequency = 0.0;
const float delay = 1.0;

auto primitive_message1 = get_messages_basic_types()[0];
primitive_message1->int32_value = test_value;
Expand All @@ -122,7 +127,7 @@ TEST_F(RosBag2PlayTestFixture, messages_played_in_loop) {
auto await_received_messages = sub_->spin_subscriptions();

rosbag2_transport::PlayOptions play_options{read_ahead_queue_size, "", rate, {}, {},
loop_playback, {}};
loop_playback, {}, clock_publish_frequency, delay};
auto player = std::make_shared<rosbag2_transport::Player>(
std::move(
reader), storage_options_, play_options);
Expand Down
61 changes: 61 additions & 0 deletions rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,3 +191,64 @@ TEST_F(PlayerTestFixture, playing_respects_rate)
ASSERT_THAT(replay_time, Gt(message_time_difference));
}
}

TEST_F(PlayerTestFixture, playing_respects_delay)
{
auto primitive_message1 = get_messages_strings()[0];
primitive_message1->string_value = "Hello World 1";

auto primitive_message2 = get_messages_strings()[0];
primitive_message2->string_value = "Hello World 2";

auto message_time_difference = std::chrono::seconds(1);
auto topics_and_types =
std::vector<rosbag2_storage::TopicMetadata>{{"topic1", "test_msgs/Strings", "", ""}};
std::vector<std::shared_ptr<rosbag2_storage::SerializedBagMessage>> messages =
{serialize_test_message("topic1", 0, primitive_message1),
serialize_test_message("topic1", 0, primitive_message2)};

messages[0]->time_stamp = 100;
messages[1]->time_stamp =
messages[0]->time_stamp + std::chrono::nanoseconds(message_time_difference).count();

float delay_margin = 1.0;

// Sleep 5.0 seconds after play
{
play_options_.delay = 5.0;
std::chrono::duration<float> delay(play_options_.delay);
std::chrono::duration<float> delay_uppper(play_options_.delay + delay_margin);

auto prepared_mock_reader = std::make_unique<MockSequentialReader>();
prepared_mock_reader->prepare(messages, topics_and_types);
auto reader = std::make_unique<rosbag2_cpp::Reader>(std::move(prepared_mock_reader));
auto player = std::make_shared<rosbag2_transport::Player>(
std::move(
reader), storage_options_, play_options_);
auto start = std::chrono::steady_clock::now();
player->play();
auto replay_time = std::chrono::steady_clock::now() - start;

ASSERT_THAT(replay_time, Gt(message_time_difference + delay));
ASSERT_THAT(replay_time, Lt(message_time_difference + delay_uppper));
}

// Invalid value should result in playing at default delay 0.0
{
play_options_.delay = -5.0;
std::chrono::duration<float> delay_uppper(delay_margin);

auto prepared_mock_reader = std::make_unique<MockSequentialReader>();
prepared_mock_reader->prepare(messages, topics_and_types);
auto reader = std::make_unique<rosbag2_cpp::Reader>(std::move(prepared_mock_reader));
auto player = std::make_shared<rosbag2_transport::Player>(
std::move(
reader), storage_options_, play_options_);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nitpick. It would be better if

    std::move(
        reader), storage_options_, play_options_);

would be on one line

    std::move(reader), storage_options_, play_options_);

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, I modified all same part in 75eca9f.

auto start = std::chrono::steady_clock::now();
player->play();
auto replay_time = std::chrono::steady_clock::now() - start;

ASSERT_THAT(replay_time, Gt(message_time_difference));
ASSERT_THAT(replay_time, Lt(message_time_difference + delay_uppper));
}
}