bag_player.cpp
Go to the documentation of this file.
1 #include "rosbag/bag_player.h"
2 
3 namespace rosbag
4 {
5 
9  View v(bag);
10  bag_start_ = v.getBeginTime();
11  bag_end_ = v.getEndTime();
13  playback_speed_ = 1.0;
14 }
15 
17  bag.close();
18 }
19 
21  return last_message_time_;
22 }
23 
25  bag_start_ = start;
26 }
27 
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( auto const & cb : cbs_ )
45  topics.push_back(cb.first);
46 
49 
50  for( auto const & m : view )
51  {
52  if (cbs_.find(m.getTopic()) == cbs_.end())
53  continue;
54 
56 
57  last_message_time_ = m.getTime(); /* this is the recorded time */
58  cbs_[m.getTopic()]->call(m);
59  }
60 }
61 
63  delete cbs_[topic];
64  cbs_.erase(topic);
65 }
66 
67 }
68 
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:206
rosbag::BagPlayer::BagPlayer
BagPlayer(const std::string &filename)
Definition: bag_player.cpp:6
rosbag::BagPlayer::get_time
rs2rosinternal::Time get_time()
Definition: bag_player.cpp:20
v
GLdouble v
Definition: glad/glad/glad.h:2144
string
GLsizei const GLchar *const * string
Definition: glad/glad/glad.h:2861
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:159
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:240
rmse.fname
fname
Definition: rmse.py:13
rosbag::bagmode::Read
@ Read
Definition: bag.h:165
rosbag::BagPlayer::real_time
rs2rosinternal::Time real_time(const rs2rosinternal::Time &msg_time)
Definition: bag_player.cpp:37
m
std::mutex m
Definition: test-waiting-on.cpp:126
rosbag::BagPlayer::set_end
void set_end(const rs2rosinternal::Time &end)
Definition: bag_player.cpp:28
rs2rosinternal::Time::init
static void init()
Definition: time.cpp:268
rosbag::BagPlayer::unregister_callback
void unregister_callback(const std::string &topic)
Definition: bag_player.cpp:62
rosbag::BagPlayer::set_start
void set_start(const rs2rosinternal::Time &start)
Definition: bag_player.cpp:24
rosbag::BagPlayer::bag_end_
rs2rosinternal::Time bag_end_
Definition: bag_player.h:154
rosbag::View
Definition: view.h:81
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:340
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:61
rosbag::BagPlayer::set_playback_speed
void set_playback_speed(double scale)
Definition: bag_player.cpp:32
rosbag::Bag::open
void open(std::string const &filename, uint32_t mode=bagmode::Read)
Open a bag file.
Definition: bag.cpp:97
end
GLuint GLuint end
Definition: glad/glad/glad.h:2395
rosbag::BagPlayer::start_play
void start_play()
Definition: bag_player.cpp:41
test-streaming.topic
topic
Definition: test-streaming.py:45
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:29
bag_player.h
rosbag::BagPlayer::~BagPlayer
virtual ~BagPlayer()
Definition: bag_player.cpp:16


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Fri Aug 2 2024 08:30:01