From 19df032cb2fb786e2cacfd1882cbdd63a820884b Mon Sep 17 00:00:00 2001 From: Nicola Loi Date: Fri, 6 Dec 2024 22:28:51 +0100 Subject: [PATCH] change progress bar string, change 'frequency' terms to 'update rate' Signed-off-by: Nicola Loi --- ros2bag/ros2bag/verb/play.py | 2 +- rosbag2_py/rosbag2_py/_transport.pyi | 2 +- rosbag2_py/src/rosbag2_py/_transport.cpp | 2 +- .../rosbag2_transport/play_options.hpp | 2 +- .../src/rosbag2_transport/play_options.cpp | 4 +- .../src/rosbag2_transport/player.cpp | 40 +++++++++---------- 6 files changed, 24 insertions(+), 28 deletions(-) diff --git a/ros2bag/ros2bag/verb/play.py b/ros2bag/ros2bag/verb/play.py index 96771d61d..31536d969 100644 --- a/ros2bag/ros2bag/verb/play.py +++ b/ros2bag/ros2bag/verb/play.py @@ -282,7 +282,7 @@ def main(self, *, args): # noqa: D102 play_options.service_requests_source = ServiceRequestsSource.SERVICE_INTROSPECTION else: play_options.service_requests_source = ServiceRequestsSource.CLIENT_INTROSPECTION - play_options.progress_bar_print_frequency = args.progress_bar + play_options.progress_bar_update_rate = args.progress_bar player = Player(args.log_level) try: diff --git a/rosbag2_py/rosbag2_py/_transport.pyi b/rosbag2_py/rosbag2_py/_transport.pyi index 05e2a707e..a1488d4b3 100644 --- a/rosbag2_py/rosbag2_py/_transport.pyi +++ b/rosbag2_py/rosbag2_py/_transport.pyi @@ -17,7 +17,7 @@ class PlayOptions: node_prefix: str playback_duration: float playback_until_timestamp: int - progress_bar_print_frequency: float + progress_bar_update_rate: float publish_service_requests: bool rate: float read_ahead_queue_size: int diff --git a/rosbag2_py/src/rosbag2_py/_transport.cpp b/rosbag2_py/src/rosbag2_py/_transport.cpp index 945c043e7..f9a3b8c4b 100644 --- a/rosbag2_py/src/rosbag2_py/_transport.cpp +++ b/rosbag2_py/src/rosbag2_py/_transport.cpp @@ -556,7 +556,7 @@ PYBIND11_MODULE(_transport, m) { "playback_until_timestamp", &PlayOptions::getPlaybackUntilTimestamp, &PlayOptions::setPlaybackUntilTimestamp) - .def_readwrite("progress_bar_print_frequency", &PlayOptions::progress_bar_print_frequency) + .def_readwrite("progress_bar_update_rate", &PlayOptions::progress_bar_update_rate) .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) diff --git a/rosbag2_transport/include/rosbag2_transport/play_options.hpp b/rosbag2_transport/include/rosbag2_transport/play_options.hpp index 975792112..f8bf67b0b 100644 --- a/rosbag2_transport/include/rosbag2_transport/play_options.hpp +++ b/rosbag2_transport/include/rosbag2_transport/play_options.hpp @@ -125,7 +125,7 @@ struct PlayOptions ServiceRequestsSource service_requests_source = ServiceRequestsSource::SERVICE_INTROSPECTION; // Rate in Hz at which to print progress bar. - double progress_bar_print_frequency = 3.0; + double progress_bar_update_rate = 3.0; }; } // namespace rosbag2_transport diff --git a/rosbag2_transport/src/rosbag2_transport/play_options.cpp b/rosbag2_transport/src/rosbag2_transport/play_options.cpp index c38683f51..10e608855 100644 --- a/rosbag2_transport/src/rosbag2_transport/play_options.cpp +++ b/rosbag2_transport/src/rosbag2_transport/play_options.cpp @@ -59,7 +59,7 @@ Node convert::encode( node["disable_loan_message"] = play_options.disable_loan_message; - node["progress_bar_print_frequency"] = play_options.progress_bar_print_frequency; + node["progress_bar_update_rate"] = play_options.progress_bar_update_rate; return node; } @@ -117,7 +117,7 @@ bool convert::decode( optional_assign(node, "disable_loan_message", play_options.disable_loan_message); optional_assign( - node, "progress_bar_print_frequency", play_options.progress_bar_print_frequency); + node, "progress_bar_update_rate", play_options.progress_bar_update_rate); return true; } diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index 17f093190..2903c31c3 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -317,17 +317,17 @@ class PlayerImpl std::atomic_bool is_delayed_status_{false}; void print_progress_bar_help_str() const; - // Update progress bar taking into account the frequency set by the user. + // Update progress bar taking into account the update rate set by the user. // The function should be called for regular progress bar updates, for example // after the recurrent message publishing. - // Call update_progress_bar_check_frequency function only if the function cannot run + // Call update_progress_bar_check_rate function only if the function cannot run // contemporaneously in multiple threads, i.e. function calls are already protected by a mutex: // to avoid locking overhead no new mutex inside the function is directly protecting // the access to the class attribute progress_bar_last_time_updated_. - void update_progress_bar_check_frequency( + void update_progress_bar_check_rate( const rcutils_time_point_value_t & timestamp, const PlayerStatus & status); - // Update progress bar irrespective of the frequency set by the user. + // Update progress bar irrespective of the update rate set by the user. // The function should be called for extraordinary progress bar updates, for example // when a log message is printed and we want to 'redraw' the progress bar. void update_progress_bar(const PlayerStatus & status) const; @@ -435,10 +435,10 @@ PlayerImpl::PlayerImpl( message_queue_(bag_message_chronological_recv_timestamp_comparator), keyboard_handler_(std::move(keyboard_handler)), player_service_client_manager_(std::make_shared()), - enable_progress_bar_(play_options.progress_bar_print_frequency != 0), - progress_bar_update_always_(play_options.progress_bar_print_frequency < 0), - progress_bar_update_period_(play_options.progress_bar_print_frequency != 0 ? - RCUTILS_S_TO_NS(1.0 / play_options.progress_bar_print_frequency) : + enable_progress_bar_(play_options.progress_bar_update_rate != 0), + progress_bar_update_always_(play_options.progress_bar_update_rate < 0), + progress_bar_update_period_(play_options.progress_bar_update_rate != 0 ? + RCUTILS_S_TO_NS(1.0 / play_options.progress_bar_update_rate) : std::numeric_limits::max()) { for (auto & topic : play_options_.topics_to_filter) { @@ -579,8 +579,6 @@ bool PlayerImpl::play() } RCLCPP_INFO_STREAM(owner_->get_logger(), "Playback until timestamp: " << play_until_timestamp_); - RCLCPP_INFO_STREAM(owner_->get_logger(), "Duration of the rosbag: " << std::fixed << - std::setprecision(9) << duration_secs_ << " s"); // May need to join the previous thread if we are calling play() a second time if (playback_thread_.joinable()) { @@ -1110,9 +1108,9 @@ void PlayerImpl::play_messages_from_queue() finished_play_next_cv_.notify_all(); } } else { - // update_progress_bar_check_frequency in this code section is protected + // update_progress_bar_check_rate in this code section is protected // by the mutex skip_message_in_main_play_loop_mutex_. - update_progress_bar_check_frequency( + update_progress_bar_check_rate( message_ptr->recv_timestamp, PlayerStatus::RUNNING); } } @@ -1740,21 +1738,19 @@ void PlayerImpl::print_progress_bar_help_str() const } else { std::ostringstream oss; oss << "Progress bar enabled at " << - play_options_.progress_bar_print_frequency << " Hz"; + play_options_.progress_bar_update_rate << " Hz"; help_str = oss.str(); } RCLCPP_INFO_STREAM(owner_->get_logger(), help_str); - std::string help_str2 = "Progress bar t: time, d: duration"; + std::string help_str2 = "Progress bar [?]: [R]unning, [P]aused, [B]urst, [D]elayed"; RCLCPP_INFO_STREAM(owner_->get_logger(), help_str2); - std::string help_str3 = "Progress bar [?]: [R]unning, [P]aused, [B]urst, [D]elayed"; - RCLCPP_INFO_STREAM(owner_->get_logger(), help_str3); } else { help_str = "Progress bar disabled"; RCLCPP_INFO_STREAM(owner_->get_logger(), help_str); } } -void PlayerImpl::update_progress_bar_check_frequency( +void PlayerImpl::update_progress_bar_check_rate( const rcutils_time_point_value_t & timestamp, const PlayerStatus & status) { @@ -1763,7 +1759,7 @@ void PlayerImpl::update_progress_bar_check_frequency( } // If we are not updating the progress bar for every call, check if we should update it now - // based on the frequency set by the user + // based on the update rate set by the user if (!progress_bar_update_always_) { std::chrono::steady_clock::time_point steady_time_now = std::chrono::steady_clock::now(); if (std::chrono::duration_cast( @@ -1783,7 +1779,7 @@ void PlayerImpl::update_progress_bar(const PlayerStatus & status) const return; } - // Update progress bar irrespective of the frequency set by the user. + // Update progress bar irrespective of the update rate set by the user. // Overwrite the input status if we are in a special case. if (is_delayed_status_) { cout_progress_bar(starting_time_, PlayerStatus::DELAYED); @@ -1802,9 +1798,9 @@ void PlayerImpl::cout_progress_bar( // Spaces before '\r' are to clear any previous progress bar in case the new one is shorter, // which can happen when the playback starts a new loop. std::ostringstream oss; - oss << " Bag t: " << std::setw(13) << std::fixed << std::setprecision(9) << - current_time_secs << " d: " << std::setprecision(9) << progress_secs << - " [" << static_cast(status) << "] \r"; + oss << "[" << std::setw(13) << std::fixed << std::setprecision(9) << current_time_secs << + "] Duration " << std::setprecision(2) << progress_secs << + "/" << duration_secs_ << " [" << static_cast(status) << "] \r"; std::cout << oss.str() << std::flush; }