playable_bag.h
Go to the documentation of this file.
1 /*
2  * Copyright 2018 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_PLAYABLE_BAG_H
18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_PLAYABLE_BAG_H
19 #include <functional>
20 #include <queue>
21 
22 #include "rosbag/bag.h"
23 #include "rosbag/view.h"
24 #include "tf2_ros/buffer.h"
25 
26 namespace cartographer_ros {
27 
28 class PlayableBag {
29  public:
30  // Handles messages early, i.e. when they are about to enter the buffer.
31  // Returns a boolean indicating whether the message should enter the buffer.
33  std::function<bool /* forward_message_to_buffer */ (
35 
36  PlayableBag(const std::string& bag_filename, int bag_id, ros::Time start_time,
37  ros::Time end_time, ros::Duration buffer_delay,
38  FilteringEarlyMessageHandler filtering_early_message_handler);
39 
40  ros::Time PeekMessageTime() const;
42  bool IsMessageAvailable() const;
43  std::tuple<ros::Time, ros::Time> GetBeginEndTime() const;
44 
45  int bag_id() const;
46 
47  private:
48  void AdvanceOneMessage();
50 
51  std::unique_ptr<rosbag::Bag> bag_;
52  std::unique_ptr<rosbag::View> view_;
54  bool finished_;
55  const int bag_id_;
56  const std::string bag_filename_;
57  const double duration_in_seconds_;
59  std::deque<rosbag::MessageInstance> buffered_messages_;
60  const ::ros::Duration buffer_delay_;
62 };
63 
65  public:
66  void AddPlayableBag(PlayableBag playable_bag);
67 
68  // Returns the next message from the multiplexed (merge-sorted) message
69  // stream, along with the bag id corresponding to the message, and whether
70  // this was the last message in that bag.
71  std::tuple<rosbag::MessageInstance, int /* bag_id */,
72  bool /* is_last_message_in_bag */>
74 
75  bool IsMessageAvailable() const;
76  ros::Time PeekMessageTime() const;
77 
78  private:
79  struct BagMessageItem {
81  int bag_index;
83  bool operator()(const BagMessageItem& l, const BagMessageItem& r) {
85  }
86  };
87  };
88 
89  std::vector<PlayableBag> playable_bags_;
90  std::priority_queue<BagMessageItem, std::vector<BagMessageItem>,
93 };
94 
95 } // namespace cartographer_ros
96 
97 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_PLAYABLE_BAG_H
const std::string bag_filename_
Definition: playable_bag.h:56
bool operator()(const BagMessageItem &l, const BagMessageItem &r)
Definition: playable_bag.h:83
std::unique_ptr< rosbag::View > view_
Definition: playable_bag.h:52
std::tuple< ros::Time, ros::Time > GetBeginEndTime() const
Definition: playable_bag.cc:53
const ::ros::Duration buffer_delay_
Definition: playable_bag.h:60
std::deque< rosbag::MessageInstance > buffered_messages_
Definition: playable_bag.h:59
FilteringEarlyMessageHandler filtering_early_message_handler_
Definition: playable_bag.h:61
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)
Definition: playable_bag.cc:26
std::vector< PlayableBag > playable_bags_
Definition: playable_bag.h:89
std::unique_ptr< rosbag::Bag > bag_
Definition: playable_bag.h:51
rosbag::View::const_iterator view_iterator_
Definition: playable_bag.h:53
rosbag::MessageInstance GetNextMessage()
Definition: playable_bag.cc:57
iterator const_iterator
std::function< bool(const rosbag::MessageInstance &)> FilteringEarlyMessageHandler
Definition: playable_bag.h:34
ros::Time PeekMessageTime() const
Definition: playable_bag.cc:48
std::priority_queue< BagMessageItem, std::vector< BagMessageItem >, BagMessageItem::TimestampIsGreater > next_message_queue_
Definition: playable_bag.h:92


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05