Skip to content

Commit

Permalink
Fix format using Uncrustify
Browse files Browse the repository at this point in the history
  • Loading branch information
kosuke55 committed Jun 24, 2021
1 parent 0b4687f commit 688fc5a
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 8 deletions.
10 changes: 5 additions & 5 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -215,13 +215,13 @@ void Player::play()
is_in_play_ = true;

float delay;
if (play_options_.delay > 0.0){
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);

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

Expand Down
8 changes: 5 additions & 3 deletions rosbag2_transport/test/rosbag2_transport/test_play_loop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ 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, {},
clock_publish_frequency, delay};
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 @@ -103,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 @@ -125,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

0 comments on commit 688fc5a

Please sign in to comment.