Skip to content

Commit

Permalink
remove new progress bar class, integrate functionality in PlayerImpl
Browse files Browse the repository at this point in the history
Signed-off-by: Nicola Loi <[email protected]>
  • Loading branch information
nicolaloi committed Oct 20, 2024
1 parent 2cb732d commit 4ba1a8c
Show file tree
Hide file tree
Showing 2 changed files with 65 additions and 105 deletions.

This file was deleted.

82 changes: 65 additions & 17 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@
#include "rosbag2_transport/config_options_from_node_params.hpp"
#include "rosbag2_transport/player_service_client.hpp"
#include "rosbag2_transport/reader_writer_factory.hpp"
#include "rosbag2_transport/player_progress_bar.hpp"

#include "logging.hpp"

Expand Down Expand Up @@ -299,6 +298,11 @@ class PlayerImpl
void configure_play_until_timestamp();
bool shall_stop_at_timestamp(const rcutils_time_point_value_t & msg_timestamp) const;

void print_status(const char status) const;
void print_running_status() const;
void print_paused_status() const;
void print_delayed_status() const;

static constexpr double read_ahead_lower_bound_percentage_ = 0.9;
static const std::chrono::milliseconds queue_read_wait_period_;
std::atomic_bool cancel_wait_for_next_message_{false};
Expand Down Expand Up @@ -329,6 +333,8 @@ class PlayerImpl
std::condition_variable playback_finished_cv_;

rcutils_time_point_value_t starting_time_;
double starting_time_secs_;
double duration_secs_;

// control services
rclcpp::Service<rosbag2_interfaces::srv::Pause>::SharedPtr srv_pause_;
Expand All @@ -352,7 +358,7 @@ class PlayerImpl
std::shared_ptr<PlayerServiceClientManager> player_service_client_manager_;

// progress bar
std::unique_ptr<PlayerProgressBar> progress_bar_;
const bool disable_progress_bar_;
};

PlayerImpl::PlayerImpl(
Expand All @@ -365,7 +371,8 @@ PlayerImpl::PlayerImpl(
storage_options_(storage_options),
play_options_(play_options),
keyboard_handler_(std::move(keyboard_handler)),
player_service_client_manager_(std::make_shared<PlayerServiceClientManager>())
player_service_client_manager_(std::make_shared<PlayerServiceClientManager>()),
disable_progress_bar_(play_options.disable_progress_bar)
{
for (auto & topic : play_options_.topics_to_filter) {
topic = rclcpp::expand_topic_or_service_name(
Expand Down Expand Up @@ -412,19 +419,25 @@ PlayerImpl::PlayerImpl(
starting_time_ += play_options_.start_offset;
bag_duration -= play_options_.start_offset;
}
starting_time_secs_ = RCUTILS_NS_TO_S(static_cast<double>(starting_time_));
duration_secs_ = RCUTILS_NS_TO_S(static_cast<double>(bag_duration));
clock_ = std::make_unique<rosbag2_cpp::TimeControllerClock>(
starting_time_, std::chrono::steady_clock::now,
std::chrono::milliseconds{100}, play_options_.start_paused);
progress_bar_ = std::make_unique<PlayerProgressBar>(play_options_.disable_progress_bar,
starting_time_, bag_duration);
set_rate(play_options_.rate);
topic_qos_profile_overrides_ = play_options_.topic_qos_profile_overrides;
prepare_publishers();
configure_play_until_timestamp();
}
create_control_services();
add_keyboard_callbacks();
RCLCPP_INFO_STREAM(owner_->get_logger(), progress_bar_->get_help_str());
std::string progress_bar_help_str;
if (!disable_progress_bar_) {
progress_bar_help_str = "Bag Time and Duration [?]: ? = R running, P paused, D delayed";
} else {
progress_bar_help_str = "Bag Time and Duration progress bar disabled.";
}
RCLCPP_INFO_STREAM(owner_->get_logger(), progress_bar_help_str);
}

PlayerImpl::~PlayerImpl()
Expand All @@ -445,6 +458,11 @@ PlayerImpl::~PlayerImpl()
if (reader_) {
reader_->close();
}
// print new line to keep on screen the latest progress bar
if (!disable_progress_bar_) {
printf("\n");
fflush(stdout);
}
}

const std::chrono::milliseconds
Expand Down Expand Up @@ -495,7 +513,7 @@ bool PlayerImpl::play()
do {
if (delay > rclcpp::Duration(0, 0)) {
RCLCPP_INFO_STREAM(owner_->get_logger(), "Sleep " << delay.nanoseconds() << " ns");
progress_bar_->print_delayed_status(clock_->now());
print_delayed_status();
std::chrono::nanoseconds delay_duration(delay.nanoseconds());
std::this_thread::sleep_for(delay_duration);
}
Expand Down Expand Up @@ -613,24 +631,24 @@ void PlayerImpl::stop()
}
}
if (clock_->is_paused()) {
progress_bar_->print_paused_status(clock_->now());
print_paused_status();
} else {
progress_bar_->print_running_status(clock_->now());
print_running_status();
}
}

void PlayerImpl::pause()
{
clock_->pause();
RCLCPP_INFO_STREAM(owner_->get_logger(), "Pausing play.");
progress_bar_->print_paused_status(clock_->now());
print_paused_status();
}

void PlayerImpl::resume()
{
clock_->resume();
RCLCPP_INFO_STREAM(owner_->get_logger(), "Resuming play.");
progress_bar_->print_running_status(clock_->now());
print_running_status();
}

void PlayerImpl::toggle_paused()
Expand Down Expand Up @@ -658,9 +676,9 @@ bool PlayerImpl::set_rate(double rate)
RCLCPP_WARN_STREAM(owner_->get_logger(), "Failed to set rate to invalid value " << rate);
}
if (clock_->is_paused()) {
progress_bar_->print_paused_status(clock_->now());
print_paused_status();
} else {
progress_bar_->print_running_status(clock_->now());
print_running_status();
}
return ok;
}
Expand Down Expand Up @@ -729,7 +747,7 @@ bool PlayerImpl::play_next()
next_message_published = publish_message(message_ptr);
clock_->jump(message_ptr->recv_timestamp);

progress_bar_->print_paused_status(clock_->now());
print_paused_status();
message_queue_.pop();
message_ptr = peek_next_message_from_queue();
}
Expand All @@ -740,7 +758,7 @@ size_t PlayerImpl::burst(const size_t num_messages)
{
if (!clock_->is_paused()) {
RCLCPP_WARN_STREAM(owner_->get_logger(), "Burst can only be used when in the paused state.");
progress_bar_->print_running_status(clock_->now());
print_running_status();
return 0;
}

Expand All @@ -755,7 +773,7 @@ size_t PlayerImpl::burst(const size_t num_messages)
}

RCLCPP_INFO_STREAM(owner_->get_logger(), "Burst " << messages_played << " messages.");
progress_bar_->print_running_status(clock_->now());
print_running_status();
return messages_played;
}

Expand Down Expand Up @@ -981,7 +999,7 @@ void PlayerImpl::play_messages_from_queue()
continue;
}
publish_message(message_ptr);
progress_bar_->print_running_status(clock_->now());
print_running_status();
}
message_queue_.pop();
message_ptr = peek_next_message_from_queue();
Expand Down Expand Up @@ -1553,6 +1571,36 @@ const rosbag2_transport::PlayOptions & PlayerImpl::get_play_options()
return play_options_;
}

inline void PlayerImpl::print_status(const char status) const
{
double current_time_secs = RCUTILS_NS_TO_S(static_cast<double>(clock_->now()));
double progress_secs = current_time_secs - starting_time_secs_;
printf(" Bag Time %13.6f Duration %.6f/%.6f [%c] \r",
current_time_secs, progress_secs, duration_secs_, status);
fflush(stdout);
}

inline void PlayerImpl::print_running_status() const
{
if (!disable_progress_bar_) {
print_status('R');
}
}

inline void PlayerImpl::print_paused_status() const
{
if (!disable_progress_bar_) {
print_status('P');
}
}

inline void PlayerImpl::print_delayed_status() const
{
if (!disable_progress_bar_) {
print_status('D');
}
}

///////////////////////////////
// Player public interface

Expand Down

0 comments on commit 4ba1a8c

Please sign in to comment.