bag_player.cpp
Go to the documentation of this file.
1 #include "rosbag/bag_player.h"
2 
3 namespace rosbag
4 {
5 
6 BagPlayer::BagPlayer(const std::string &fname) {
9  View v(bag);
11  bag_end_ = v.getEndTime();
13  playback_speed_ = 1.0;
14 }
15 
17  bag.close();
18 }
19 
21  return last_message_time_;
22 }
23 
24 void BagPlayer::set_start(const ros::Time &start) {
25  bag_start_ = start;
26 }
27 
28 void BagPlayer::set_end(const ros::Time &end) {
29  bag_end_ = end;
30 }
31 
32 void BagPlayer::set_playback_speed(double scale) {
33  if (scale > 0.0)
34  playback_speed_ = scale;
35 }
36 
38  return play_start_ + (msg_time - bag_start_) * (1 / playback_speed_);
39 }
40 
42 
43  std::vector<std::string> topics;
44  for (const auto& cb : cbs_)
45  topics.push_back(cb.first);
46 
47  View view(bag, TopicQuery(topics), bag_start_, bag_end_);
49 
50  for (MessageInstance const& m : view)
51  {
52  if (cbs_.find(m.getTopic()) == cbs_.end())
53  continue;
54 
55  ros::Time::sleepUntil(real_time(m.getTime()));
56 
57  last_message_time_ = m.getTime(); /* this is the recorded time */
58  cbs_[m.getTopic()]->call(m);
59  }
60 }
61 
62 void BagPlayer::unregister_callback(const std::string &topic) {
63  cbs_.erase(topic);
64 }
65 
66 }
67 
ros::Time real_time(const ros::Time &msg_time)
Definition: bag_player.cpp:37
void open(std::string const &filename, uint32_t mode=bagmode::Read)
Open a bag file.
Definition: bag.cpp:103
static bool sleepUntil(const Time &end)
void set_playback_speed(double scale)
Definition: bag_player.cpp:32
void set_start(const ros::Time &start)
Definition: bag_player.cpp:24
std::map< std::string, boost::shared_ptr< BagCallback > > cbs_
Definition: bag_player.h:135
void unregister_callback(const std::string &topic)
Definition: bag_player.cpp:62
ros::Time get_time()
Definition: bag_player.cpp:20
ros::Time play_start_
Definition: bag_player.h:140
void close()
Close the bag file.
Definition: bag.cpp:163
ros::Time bag_start_
Definition: bag_player.h:136
virtual ~BagPlayer()
Definition: bag_player.cpp:16
ros::Time last_message_time_
Definition: bag_player.h:138
ros::Time getBeginTime()
Definition: view.cpp:184
A class pointing into a bag file.
void set_end(const ros::Time &end)
Definition: bag_player.cpp:28
static void init()
BagPlayer(const std::string &filename)
Definition: bag_player.cpp:6
double playback_speed_
Definition: bag_player.h:139
ros::Time bag_end_
Definition: bag_player.h:137
ros::Time getEndTime()
Definition: view.cpp:199
static Time now()


rosbag_storage
Author(s): Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:55