fix: Use an explicit message_counter instead of using `std::distance` (#1045)

As @ojura reported and explained in #940, there is a critical issue with the new changes introduced in the mentioned PR, which significantly slows down the offline node. 
- The reason of this problem was that In order to count the number of processed messages the `std::distance` function was used which is computationally expensive(O(n)).
- Instead, the former `log_counter_` and now `message_counter_` class variable which was used to print a message every X seconds is also employed to count the number of the processed (and also skipped) messages.
master
Alireza 2018-10-09 15:26:48 +02:00 committed by Wally B. Feed
parent 588c392b50
commit 5f2dff9df0
2 changed files with 5 additions and 5 deletions

View File

@ -36,7 +36,7 @@ PlayableBag::PlayableBag(
bag_filename_(bag_filename), bag_filename_(bag_filename),
duration_in_seconds_( duration_in_seconds_(
(view_->getEndTime() - view_->getBeginTime()).toSec()), (view_->getEndTime() - view_->getBeginTime()).toSec()),
log_counter_(0), message_counter_(0),
buffer_delay_(buffer_delay), buffer_delay_(buffer_delay),
filtering_early_message_handler_( filtering_early_message_handler_(
std::move(filtering_early_message_handler)) { std::move(filtering_early_message_handler)) {
@ -62,7 +62,7 @@ rosbag::MessageInstance PlayableBag::GetNextMessage(
buffered_messages_.pop_front(); buffered_messages_.pop_front();
AdvanceUntilMessageAvailable(); AdvanceUntilMessageAvailable();
double processed_seconds = (msg.getTime() - view_->getBeginTime()).toSec(); double processed_seconds = (msg.getTime() - view_->getBeginTime()).toSec();
if ((log_counter_++ % 10000) == 0) { if ((message_counter_ % 10000) == 0) {
LOG(INFO) << "Processed " << processed_seconds << " of " LOG(INFO) << "Processed " << processed_seconds << " of "
<< duration_in_seconds_ << " seconds of bag " << bag_filename_; << duration_in_seconds_ << " seconds of bag " << bag_filename_;
} }
@ -71,8 +71,7 @@ rosbag::MessageInstance PlayableBag::GetNextMessage(
progress->current_bagfile_name = bag_filename_; progress->current_bagfile_name = bag_filename_;
progress->current_bagfile_id = bag_id_; progress->current_bagfile_id = bag_id_;
progress->total_messages = view_->size(); progress->total_messages = view_->size();
progress->processed_messages = progress->processed_messages = message_counter_;
std::distance(view_->begin(), view_iterator_);
progress->total_seconds = duration_in_seconds_; progress->total_seconds = duration_in_seconds_;
progress->processed_seconds = processed_seconds; progress->processed_seconds = processed_seconds;
} }
@ -100,6 +99,7 @@ void PlayableBag::AdvanceOneMessage() {
buffered_messages_.push_back(msg); buffered_messages_.push_back(msg);
} }
++view_iterator_; ++view_iterator_;
++message_counter_;
} }
void PlayableBag::AdvanceUntilMessageAvailable() { void PlayableBag::AdvanceUntilMessageAvailable() {

View File

@ -59,7 +59,7 @@ class PlayableBag {
const int bag_id_; const int bag_id_;
const std::string bag_filename_; const std::string bag_filename_;
const double duration_in_seconds_; const double duration_in_seconds_;
int log_counter_; int message_counter_;
std::deque<rosbag::MessageInstance> buffered_messages_; std::deque<rosbag::MessageInstance> buffered_messages_;
const ::ros::Duration buffer_delay_; const ::ros::Duration buffer_delay_;
FilteringEarlyMessageHandler filtering_early_message_handler_; FilteringEarlyMessageHandler filtering_early_message_handler_;