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

Progress-bar for ros2 bag play #1836

Open
wants to merge 36 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
36 commits
Select commit Hold shift + click to select a range
616df0d
Start adding progress-bar for ros2 bag play
nicolaloi Oct 15, 2024
2cb732d
clean #include
nicolaloi Oct 15, 2024
4ba1a8c
remove new progress bar class, integrate functionality in PlayerImpl
nicolaloi Oct 20, 2024
a00bdc4
convert to template
nicolaloi Oct 23, 2024
43fa0f8
Code review
nicolaloi Oct 28, 2024
9cdf5ad
update default rate
nicolaloi Nov 10, 2024
bac4e9f
update to avoid synchronization issues
nicolaloi Nov 17, 2024
0c99597
add burst status, reduce cout setprecision
nicolaloi Nov 18, 2024
372b8a2
Merge branch 'rolling' into nicolaloi/bag-play-progress-bar
nicolaloi Dec 2, 2024
6051e6c
some updates after merge with rolling
nicolaloi Dec 2, 2024
0ef3f26
comments
nicolaloi Dec 4, 2024
47dff3d
Progress bar with nanosecond precision and shorter length
nicolaloi Dec 5, 2024
19df032
change progress bar string, change 'frequency' terms to 'update rate'
nicolaloi Dec 6, 2024
fb464b0
comments
nicolaloi Dec 6, 2024
6a47a7f
Merge branch 'rolling' into nicolaloi/bag-play-progress-bar
nicolaloi Dec 8, 2024
8625164
add custom space between playback output and progress bar
nicolaloi Dec 8, 2024
913de31
stubgen
nicolaloi Dec 8, 2024
5ed1994
Add test_xmllint.py to python packages. (#1879)
clalancette Dec 10, 2024
ab7cd93
Add more logging info to storage and reader/writer open operations (#…
MichaelOrlov Dec 12, 2024
79ae2d0
Increase timeout to 180s for test_rosbag2_record_end_to_end (#1889)
Yadunund Dec 28, 2024
a7aa5f0
Bugfix. Event publisher not starting for second run after stop (#1888)
MichaelOrlov Dec 30, 2024
1f99a37
Bugfix: Recorder discovery does not restart after being stopped (#1894)
oysstu Jan 22, 2025
6e75a9d
Change type of progress_bar_update_rate to int32_t
MichaelOrlov Jan 11, 2025
ec11778
Remove "in_burst_mode" from play_next() method
MichaelOrlov Jan 11, 2025
510a248
Move progress bar to a separate PlayerProgressBar class
MichaelOrlov Jan 25, 2025
681c1ed
Move PlayerStatus inside PlayerProgressBar
MichaelOrlov Jan 26, 2025
3a8301b
Move PlayerProgressBar class to a separate h(c)pp files
MichaelOrlov Jan 26, 2025
bb8dc2a
Use Pimpl design pattern for PlayerProgressBar class
MichaelOrlov Jan 26, 2025
8798397
Replace logger and std::cout with reference to the std::ostream
MichaelOrlov Jan 26, 2025
8e45042
Use std::stringstream and rdbuf() to avoid extra data copy to string
MichaelOrlov Jan 26, 2025
295e137
Change type of the `progress_bar_separation_lines` to the `uint32_t`
MichaelOrlov Jan 26, 2025
36e07c5
Simplify logic by using update period in milliseconds
MichaelOrlov Jan 26, 2025
3709879
Regenerate pyi stub files
MichaelOrlov Jan 26, 2025
2f6e66b
Add test_player_progress_bar.cpp with TODOs
MichaelOrlov Jan 26, 2025
74bc915
Add some unit tests
nicolaloi Jan 30, 2025
0995532
Merge branch 'rolling' into nicolaloi/bag-play-progress-bar
nicolaloi Jan 30, 2025
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 docs/design/rosbag2_record_replay_service.md
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,10 @@ Added or changed parameters:

Rename from `--exclude`. Exclude topics and services containing provided regular expression.

- `--progress-bar [ProgressBarFrequency]`

Print a progress bar of the playback player at a specific frequency in Hz. Negative values mark an update for every published message, while a zero value disables the progress bar. Default to a positive low value.

`-e REGEX, --regex REGEX` affects both topics and services.

## Implementation Staging
Expand Down
20 changes: 20 additions & 0 deletions ros2bag/ros2bag/verb/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,23 @@ def add_arguments(self, parser, cli_name): # noqa: D102
'--log-level', type=str, default='info',
choices=['debug', 'info', 'warn', 'error', 'fatal'],
help='Logging level.')
parser.add_argument(
'--progress-bar', type=int, default=3,
help='Print a progress bar for the playback at a specific rate in times per second. '
'Default is %(default)d. '
'Negative values mark an update for every published message, while '
' a zero value disables the progress bar.',
metavar='PROGRESS_BAR_UPDATE_RATE')
parser.add_argument(
'--progress-bar-separation-lines', type=check_not_negative_int, default=2,
help='Number of lines to separate the progress bar from the rest of the '
'playback player output. Negative values are invalid. Default is %(default)d. '
'This option makes sense only if the progress bar is enabled. '
'Large values are useful if external log messages from other nodes are shorter '
'than the progress bar string and are printed at a rate higher than the '
'progress bar update rate. In these cases, a larger value will avoid '
'the external log message to be mixed with the progress bar string.',
metavar='NUM_SEPARATION_LINES')

def get_playback_until_from_arg_group(self, playback_until_sec, playback_until_nsec) -> int:
nano_scale = 1000 * 1000 * 1000
Expand Down Expand Up @@ -292,6 +309,9 @@ def main(self, *, args): # noqa: D102
'sent': MessageOrder.SENT_TIMESTAMP,
}.get(args.message_order)

play_options.progress_bar_update_rate = args.progress_bar
play_options.progress_bar_separation_lines = args.progress_bar_separation_lines

player = Player(args.log_level)
try:
player.play(storage_options, play_options)
Expand Down
2 changes: 2 additions & 0 deletions rosbag2_py/rosbag2_py/_transport.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@ class PlayOptions:
node_prefix: str
playback_duration: float
playback_until_timestamp: int
progress_bar_separation_lines: int
progress_bar_update_rate: int
publish_service_requests: bool
rate: float
read_ahead_queue_size: int
Expand Down
2 changes: 2 additions & 0 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -556,6 +556,8 @@ PYBIND11_MODULE(_transport, m) {
"playback_until_timestamp",
&PlayOptions::getPlaybackUntilTimestamp,
&PlayOptions::setPlaybackUntilTimestamp)
.def_readwrite("progress_bar_update_rate", &PlayOptions::progress_bar_update_rate)
.def_readwrite("progress_bar_separation_lines", &PlayOptions::progress_bar_separation_lines)
.def_readwrite("wait_acked_timeout", &PlayOptions::wait_acked_timeout)
.def_readwrite("disable_loan_message", &PlayOptions::disable_loan_message)
.def_readwrite("publish_service_requests", &PlayOptions::publish_service_requests)
Expand Down
4 changes: 4 additions & 0 deletions rosbag2_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ add_library(${PROJECT_NAME} SHARED
src/rosbag2_transport/bag_rewrite.cpp
src/rosbag2_transport/player.cpp
src/rosbag2_transport/play_options.cpp
src/rosbag2_transport/player_progress_bar.cpp
src/rosbag2_transport/player_service_client.cpp
src/rosbag2_transport/reader_writer_factory.cpp
src/rosbag2_transport/recorder.cpp
Expand Down Expand Up @@ -534,6 +535,9 @@ if(BUILD_TESTING)
rcpputils::rcpputils
rosbag2_test_common::rosbag2_test_common
)

ament_add_gmock(test_player_progress_bar test/rosbag2_transport/test_player_progress_bar.cpp)
target_link_libraries(test_player_progress_bar ${PROJECT_NAME})
endif()

ament_package()
6 changes: 6 additions & 0 deletions rosbag2_transport/include/rosbag2_transport/play_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,12 @@ struct PlayOptions
// replayed messages may not be correctly ordered. A possible solution could be to increase the
// read_ahead_queue_size value to buffer (and order) more messages.
MessageOrder message_order = MessageOrder::RECEIVED_TIMESTAMP;

// Progress bar update rate in times per second (Hz)
int32_t progress_bar_update_rate = 3;

// Number of separation lines to print in between the playback output and the progress bar.
uint32_t progress_bar_separation_lines = 3;
};

} // namespace rosbag2_transport
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
// Copyright 2025 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef ROSBAG2_TRANSPORT__PLAYER_PROGRESS_BAR_HPP_
#define ROSBAG2_TRANSPORT__PLAYER_PROGRESS_BAR_HPP_

#include <memory>
#include <string>

#include "rcutils/time.h"
#include "rosbag2_transport/visibility_control.hpp"

namespace rosbag2_transport
{
class PlayerProgressBarImpl;

class ROSBAG2_TRANSPORT_PUBLIC PlayerProgressBar
{
public:
enum class PlayerStatus : char
{
BURST = 'B',
DELAYED = 'D',
PAUSED = 'P',
RUNNING = 'R',
STOPPED = 'S',
};

/// PlayerProgressBar constructor
/// \param output_stream Reference to output stream where progress bar and help information
/// will be printed out. Could be std::cout, std::cerr or std::ostringstream for tests.
/// \param starting_time Time stamp of the first message in the bag.
/// \param ending_time Time stamp of the last message in the bag.
/// \param progress_bar_update_rate The progress bar maximum update rate in times per second (Hz).
/// If update rate equal 0 the progress bar will be disabled and will not output any information.
/// If update rate less than 0 the progress bar will be updated for every update(..) and
/// update_with_limited_rate(..) calls.
/// \param progress_bar_separation_lines Number of separation lines to print in between the
/// playback output and the progress bar.
explicit PlayerProgressBar(
std::ostream & output_stream,
rcutils_time_point_value_t starting_time,
rcutils_time_point_value_t ending_time,
int32_t progress_bar_update_rate = 3,
uint32_t progress_bar_separation_lines = 3);

virtual ~PlayerProgressBar();

/// \brief Prints help string about player progress bar.
/// Expected to be printed once at the beginning.
void print_help_str() const;

/// \brief Updates progress bar with the specified timestamp and player status, taking into
/// account the update rate set by the user.
/// \note The function should be used for regular progress bar updates, for example
/// after the publishing the next message.
/// \warning This function is not thread safe and shall not be called concurrently from multiple
/// threads.
/// \param timestamp Timestamp of the last published message.
/// \param status The player status to be updated on progress bar.
void update_with_limited_rate(
const rcutils_time_point_value_t & timestamp,
const PlayerStatus & status);

/// \brief Updates progress bar with the specified player status, irrespective to the update rate
/// set by the user.
/// \note The function should be called for extraordinary progress bar updates, for example
/// when player changed its internal status or a log message is printed, and we want to 'redraw'
/// the progress bar.
/// \param status The player status to be updated on progress bar.
void update(const PlayerStatus & status);

private:
std::unique_ptr<PlayerProgressBarImpl> pimpl_;
};

} // namespace rosbag2_transport

#endif // ROSBAG2_TRANSPORT__PLAYER_PROGRESS_BAR_HPP_
9 changes: 9 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/play_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ Node convert<rosbag2_transport::PlayOptions>::encode(

node["disable_loan_message"] = play_options.disable_loan_message;

node["progress_bar_update_rate"] = play_options.progress_bar_update_rate;
node["progress_bar_separation_lines"] = play_options.progress_bar_separation_lines;

return node;
}

Expand Down Expand Up @@ -114,6 +117,12 @@ bool convert<rosbag2_transport::PlayOptions>::decode(

optional_assign<bool>(node, "disable_loan_message", play_options.disable_loan_message);

optional_assign<int32_t>(
node, "progress_bar_update_rate", play_options.progress_bar_update_rate);

optional_assign<uint32_t>(
node, "progress_bar_separation_lines", play_options.progress_bar_separation_lines);

return true;
}

Expand Down
Loading
Loading