bag_player.cpp
Go to the documentation of this file.
1 #include "rosbag/bag_player.h"
2 
3 #define foreach BOOST_FOREACH
4 
5 namespace rosbag
6 {
7 
8 BagPlayer::BagPlayer(const std::string &fname) {
11  View v(bag);
12  bag_start_ = v.getBeginTime();
13  bag_end_ = v.getEndTime();
15  playback_speed_ = 1.0;
16 }
17 
19  bag.close();
20 }
21 
23  return last_message_time_;
24 }
25 
27  bag_start_ = start;
28 }
29 
31  bag_end_ = end;
32 }
33 
34 void BagPlayer::set_playback_speed(double scale) {
35  if (scale > 0.0)
36  playback_speed_ = scale;
37 }
38 
40  return play_start_ + (msg_time - bag_start_) * (1 / playback_speed_);
41 }
42 
44 
45  std::vector<std::string> topics;
46  std::pair<std::string, BagCallback *> cb;
47  foreach(cb, cbs_)
48  topics.push_back(cb.first);
49 
52 
53  foreach(MessageInstance const m, view)
54  {
55  if (cbs_.find(m.getTopic()) == cbs_.end())
56  continue;
57 
59 
60  last_message_time_ = m.getTime(); /* this is the recorded time */
61  cbs_[m.getTopic()]->call(m);
62  }
63 }
64 
65 void BagPlayer::unregister_callback(const std::string &topic) {
66  delete cbs_[topic];
67  cbs_.erase(topic);
68 }
69 
70 }
71 
rosbag::BagPlayer::bag
Bag bag
Definition: bag_player.h:147
rs2rosinternal::Time
Time representation. May either represent wall clock time or ROS clock time.
Definition: time.h:215
rosbag::BagPlayer::BagPlayer
BagPlayer(const std::string &filename)
Definition: bag_player.cpp:8
view
Definition: rs-trajectory.cpp:255
rosbag::MessageInstance
A class pointing into a bag file.
Definition: message_instance.h:91
rosbag::BagPlayer::get_time
rs2rosinternal::Time get_time()
Definition: bag_player.cpp:22
v
GLdouble v
Definition: glad/glad/glad.h:2144
rosbag::BagPlayer::cbs_
std::map< std::string, BagCallback * > cbs_
Definition: bag_player.h:152
rosbag::Bag::close
void close()
Close the bag file.
Definition: bag.cpp:161
rs2rosinternal::Time::now
static Time now()
Retrieve the current time. If ROS clock time is in use, this returns the time according to the ROS cl...
Definition: time.cpp:243
rmse.fname
fname
Definition: rmse.py:13
rosbag::bagmode::Read
@ Read
Definition: bag.h:170
rosbag::BagPlayer::real_time
rs2rosinternal::Time real_time(const rs2rosinternal::Time &msg_time)
Definition: bag_player.cpp:39
m
std::mutex m
Definition: test-waiting-on.cpp:124
rosbag::BagPlayer::set_end
void set_end(const rs2rosinternal::Time &end)
Definition: bag_player.cpp:30
rs2rosinternal::Time::init
static void init()
Definition: time.cpp:271
rosbag::BagPlayer::unregister_callback
void unregister_callback(const std::string &topic)
Definition: bag_player.cpp:65
rosbag::BagPlayer::set_start
void set_start(const rs2rosinternal::Time &start)
Definition: bag_player.cpp:26
rosbag::BagPlayer::bag_end_
rs2rosinternal::Time bag_end_
Definition: bag_player.h:154
rosbag::View
Definition: view.h:80
rosbag::BagPlayer::play_start_
rs2rosinternal::Time play_start_
Definition: bag_player.h:157
opencv_pointcloud_viewer.view
def view(v)
Definition: opencv_pointcloud_viewer.py:168
rs2rosinternal::Time::sleepUntil
static bool sleepUntil(const Time &end)
Sleep until a specific time has been reached.
Definition: time.cpp:353
std_msgs::Time
::std_msgs::Time_< std::allocator< void > > Time
Definition: Time.h:47
start
GLuint start
Definition: glad/glad/glad.h:2395
rosbag::TopicQuery
Definition: query.h:107
rosbag::BagPlayer::last_message_time_
rs2rosinternal::Time last_message_time_
Definition: bag_player.h:155
rosbag::BagPlayer::playback_speed_
double playback_speed_
Definition: bag_player.h:156
rosbag
Definition: bag.h:66
rosbag::BagPlayer::set_playback_speed
void set_playback_speed(double scale)
Definition: bag_player.cpp:34
rosbag::Bag::open
void open(std::string const &filename, uint32_t mode=bagmode::Read)
Open a bag file.
Definition: bag.cpp:101
end
GLuint GLuint end
Definition: glad/glad/glad.h:2395
rosbag::BagPlayer::start_play
void start_play()
Definition: bag_player.cpp:43
rosbag::BagPlayer::bag_start_
rs2rosinternal::Time bag_start_
Definition: bag_player.h:153
test-color_frame_frops.cb
def cb(frame, ts)
Definition: test-color_frame_frops.py:31
bag_player.h
rosbag::BagPlayer::~BagPlayer
virtual ~BagPlayer()
Definition: bag_player.cpp:18


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Thu Dec 22 2022 03:13:13