41
41
#include " rosbag2_transport/config_options_from_node_params.hpp"
42
42
#include " rosbag2_transport/player_service_client.hpp"
43
43
#include " rosbag2_transport/reader_writer_factory.hpp"
44
- #include " rosbag2_transport/player_progress_bar.hpp"
45
44
46
45
#include " logging.hpp"
47
46
@@ -299,6 +298,11 @@ class PlayerImpl
299
298
void configure_play_until_timestamp ();
300
299
bool shall_stop_at_timestamp (const rcutils_time_point_value_t & msg_timestamp) const ;
301
300
301
+ void print_status (const char status) const ;
302
+ void print_running_status () const ;
303
+ void print_paused_status () const ;
304
+ void print_delayed_status () const ;
305
+
302
306
static constexpr double read_ahead_lower_bound_percentage_ = 0.9 ;
303
307
static const std::chrono::milliseconds queue_read_wait_period_;
304
308
std::atomic_bool cancel_wait_for_next_message_{false };
@@ -329,6 +333,8 @@ class PlayerImpl
329
333
std::condition_variable playback_finished_cv_;
330
334
331
335
rcutils_time_point_value_t starting_time_;
336
+ double starting_time_secs_;
337
+ double duration_secs_;
332
338
333
339
// control services
334
340
rclcpp::Service<rosbag2_interfaces::srv::Pause>::SharedPtr srv_pause_;
@@ -352,7 +358,7 @@ class PlayerImpl
352
358
std::shared_ptr<PlayerServiceClientManager> player_service_client_manager_;
353
359
354
360
// progress bar
355
- std::unique_ptr<PlayerProgressBar> progress_bar_ ;
361
+ const bool disable_progress_bar_ ;
356
362
};
357
363
358
364
PlayerImpl::PlayerImpl (
@@ -365,7 +371,8 @@ PlayerImpl::PlayerImpl(
365
371
storage_options_ (storage_options),
366
372
play_options_(play_options),
367
373
keyboard_handler_(std::move(keyboard_handler)),
368
- player_service_client_manager_(std::make_shared<PlayerServiceClientManager>())
374
+ player_service_client_manager_(std::make_shared<PlayerServiceClientManager>()),
375
+ disable_progress_bar_(play_options.disable_progress_bar)
369
376
{
370
377
for (auto & topic : play_options_.topics_to_filter ) {
371
378
topic = rclcpp::expand_topic_or_service_name (
@@ -412,19 +419,25 @@ PlayerImpl::PlayerImpl(
412
419
starting_time_ += play_options_.start_offset ;
413
420
bag_duration -= play_options_.start_offset ;
414
421
}
422
+ starting_time_secs_ = RCUTILS_NS_TO_S (static_cast <double >(starting_time_));
423
+ duration_secs_ = RCUTILS_NS_TO_S (static_cast <double >(bag_duration));
415
424
clock_ = std::make_unique<rosbag2_cpp::TimeControllerClock>(
416
425
starting_time_, std::chrono::steady_clock::now,
417
426
std::chrono::milliseconds{100 }, play_options_.start_paused );
418
- progress_bar_ = std::make_unique<PlayerProgressBar>(play_options_.disable_progress_bar ,
419
- starting_time_, bag_duration);
420
427
set_rate (play_options_.rate );
421
428
topic_qos_profile_overrides_ = play_options_.topic_qos_profile_overrides ;
422
429
prepare_publishers ();
423
430
configure_play_until_timestamp ();
424
431
}
425
432
create_control_services ();
426
433
add_keyboard_callbacks ();
427
- RCLCPP_INFO_STREAM (owner_->get_logger (), progress_bar_->get_help_str ());
434
+ std::string progress_bar_help_str;
435
+ if (!disable_progress_bar_) {
436
+ progress_bar_help_str = " Bag Time and Duration [?]: ? = R running, P paused, D delayed" ;
437
+ } else {
438
+ progress_bar_help_str = " Bag Time and Duration progress bar disabled." ;
439
+ }
440
+ RCLCPP_INFO_STREAM (owner_->get_logger (), progress_bar_help_str);
428
441
}
429
442
430
443
PlayerImpl::~PlayerImpl ()
@@ -445,6 +458,11 @@ PlayerImpl::~PlayerImpl()
445
458
if (reader_) {
446
459
reader_->close ();
447
460
}
461
+ // print new line to keep on screen the latest progress bar
462
+ if (!disable_progress_bar_) {
463
+ printf (" \n " );
464
+ fflush (stdout);
465
+ }
448
466
}
449
467
450
468
const std::chrono::milliseconds
@@ -495,7 +513,7 @@ bool PlayerImpl::play()
495
513
do {
496
514
if (delay > rclcpp::Duration (0 , 0 )) {
497
515
RCLCPP_INFO_STREAM (owner_->get_logger (), " Sleep " << delay.nanoseconds () << " ns" );
498
- progress_bar_-> print_delayed_status (clock_-> now () );
516
+ print_delayed_status ();
499
517
std::chrono::nanoseconds delay_duration (delay.nanoseconds ());
500
518
std::this_thread::sleep_for (delay_duration);
501
519
}
@@ -613,24 +631,24 @@ void PlayerImpl::stop()
613
631
}
614
632
}
615
633
if (clock_->is_paused ()) {
616
- progress_bar_-> print_paused_status (clock_-> now () );
634
+ print_paused_status ();
617
635
} else {
618
- progress_bar_-> print_running_status (clock_-> now () );
636
+ print_running_status ();
619
637
}
620
638
}
621
639
622
640
void PlayerImpl::pause ()
623
641
{
624
642
clock_->pause ();
625
643
RCLCPP_INFO_STREAM (owner_->get_logger (), " Pausing play." );
626
- progress_bar_-> print_paused_status (clock_-> now () );
644
+ print_paused_status ();
627
645
}
628
646
629
647
void PlayerImpl::resume ()
630
648
{
631
649
clock_->resume ();
632
650
RCLCPP_INFO_STREAM (owner_->get_logger (), " Resuming play." );
633
- progress_bar_-> print_running_status (clock_-> now () );
651
+ print_running_status ();
634
652
}
635
653
636
654
void PlayerImpl::toggle_paused ()
@@ -658,9 +676,9 @@ bool PlayerImpl::set_rate(double rate)
658
676
RCLCPP_WARN_STREAM (owner_->get_logger (), " Failed to set rate to invalid value " << rate);
659
677
}
660
678
if (clock_->is_paused ()) {
661
- progress_bar_-> print_paused_status (clock_-> now () );
679
+ print_paused_status ();
662
680
} else {
663
- progress_bar_-> print_running_status (clock_-> now () );
681
+ print_running_status ();
664
682
}
665
683
return ok;
666
684
}
@@ -729,7 +747,7 @@ bool PlayerImpl::play_next()
729
747
next_message_published = publish_message (message_ptr);
730
748
clock_->jump (message_ptr->recv_timestamp );
731
749
732
- progress_bar_-> print_paused_status (clock_-> now () );
750
+ print_paused_status ();
733
751
message_queue_.pop ();
734
752
message_ptr = peek_next_message_from_queue ();
735
753
}
@@ -740,7 +758,7 @@ size_t PlayerImpl::burst(const size_t num_messages)
740
758
{
741
759
if (!clock_->is_paused ()) {
742
760
RCLCPP_WARN_STREAM (owner_->get_logger (), " Burst can only be used when in the paused state." );
743
- progress_bar_-> print_running_status (clock_-> now () );
761
+ print_running_status ();
744
762
return 0 ;
745
763
}
746
764
@@ -755,7 +773,7 @@ size_t PlayerImpl::burst(const size_t num_messages)
755
773
}
756
774
757
775
RCLCPP_INFO_STREAM (owner_->get_logger (), " Burst " << messages_played << " messages." );
758
- progress_bar_-> print_running_status (clock_-> now () );
776
+ print_running_status ();
759
777
return messages_played;
760
778
}
761
779
@@ -981,7 +999,7 @@ void PlayerImpl::play_messages_from_queue()
981
999
continue ;
982
1000
}
983
1001
publish_message (message_ptr);
984
- progress_bar_-> print_running_status (clock_-> now () );
1002
+ print_running_status ();
985
1003
}
986
1004
message_queue_.pop ();
987
1005
message_ptr = peek_next_message_from_queue ();
@@ -1553,6 +1571,36 @@ const rosbag2_transport::PlayOptions & PlayerImpl::get_play_options()
1553
1571
return play_options_;
1554
1572
}
1555
1573
1574
+ inline void PlayerImpl::print_status (const char status) const
1575
+ {
1576
+ double current_time_secs = RCUTILS_NS_TO_S (static_cast <double >(clock_->now ()));
1577
+ double progress_secs = current_time_secs - starting_time_secs_;
1578
+ printf (" Bag Time %13.6f Duration %.6f/%.6f [%c] \r " ,
1579
+ current_time_secs, progress_secs, duration_secs_, status);
1580
+ fflush (stdout);
1581
+ }
1582
+
1583
+ inline void PlayerImpl::print_running_status () const
1584
+ {
1585
+ if (!disable_progress_bar_) {
1586
+ print_status (' R' );
1587
+ }
1588
+ }
1589
+
1590
+ inline void PlayerImpl::print_paused_status () const
1591
+ {
1592
+ if (!disable_progress_bar_) {
1593
+ print_status (' P' );
1594
+ }
1595
+ }
1596
+
1597
+ inline void PlayerImpl::print_delayed_status () const
1598
+ {
1599
+ if (!disable_progress_bar_) {
1600
+ print_status (' D' );
1601
+ }
1602
+ }
1603
+
1556
1604
// /////////////////////////////
1557
1605
// Player public interface
1558
1606
0 commit comments