17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_PLAYABLE_BAG_H 18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_PLAYABLE_BAG_H 51 std::unique_ptr<rosbag::Bag>
bag_;
52 std::unique_ptr<rosbag::View>
view_;
90 std::priority_queue<BagMessageItem, std::vector<BagMessageItem>,
97 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_PLAYABLE_BAG_H
const std::string bag_filename_
bool operator()(const BagMessageItem &l, const BagMessageItem &r)
std::unique_ptr< rosbag::View > view_
const double duration_in_seconds_
std::tuple< ros::Time, ros::Time > GetBeginEndTime() const
const ::ros::Duration buffer_delay_
std::deque< rosbag::MessageInstance > buffered_messages_
ros::Time message_timestamp
FilteringEarlyMessageHandler filtering_early_message_handler_
PlayableBag(const std::string &bag_filename, int bag_id, ros::Time start_time, ros::Time end_time, ros::Duration buffer_delay, FilteringEarlyMessageHandler filtering_early_message_handler)
std::vector< PlayableBag > playable_bags_
std::unique_ptr< rosbag::Bag > bag_
bool IsMessageAvailable() const
void AdvanceUntilMessageAvailable()
rosbag::View::const_iterator view_iterator_
rosbag::MessageInstance GetNextMessage()
std::function< bool(const rosbag::MessageInstance &)> FilteringEarlyMessageHandler
ros::Time PeekMessageTime() const
std::priority_queue< BagMessageItem, std::vector< BagMessageItem >, BagMessageItem::TimestampIsGreater > next_message_queue_