bag_player.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Open Source Robotics Foundation
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef ROSBAG_BAG_PLAYER_H
36 #define ROSBAG_BAG_PLAYER_H
37 
38 #include "rosbag/bag.h"
39 #include "rosbag/view.h"
40 
41 #include <functional>
42 
43 namespace rosbag
44 {
45 
46 
47 // A helper struct
48 struct BagCallback
49 {
50  virtual ~BagCallback() {};
51  virtual void call(MessageInstance m) = 0;
52 };
53 
54 // A helper class for the callbacks
55 template<class T>
56 class BagCallbackT : public BagCallback
57 {
58 public:
59  typedef std::function<void (const std::shared_ptr<const T>&)> Callback;
60 
62  cb_(cb)
63  {}
64 
65  void call(MessageInstance m) {
66  cb_(m.instantiate<T>());
67  }
68 
69 private:
70  Callback cb_;
71 };
72 #ifdef _MSC_VER
73 //#pragma warning( disable : 4290 ) // Suppress warning C4290:C++ exception specification ignored except to indicate a function is not __declspec(nothrow)
74 #endif
75 /* A class for playing back bag files at an API level. It supports
76  relatime, as well as accelerated and slowed playback. */
77 class BagPlayer
78 {
79 public:
80  /* Constructor expecting the filename of a bag */
82 
83  /* Register a callback for a specific topic and type */
84  template<class T>
86  typename BagCallbackT<T>::Callback f);
87 
88  /* Unregister a callback for a topic already registered */
90 
91  /* Set the time in the bag to start.
92  * Default is the first message */
94 
95  /* Set the time in the bag to stop.
96  * Default is the last message */
98 
99  /* Set the speed to playback. 1.0 is the default.
100  * 2.0 would be twice as fast, 0.5 is half realtime. */
101  void set_playback_speed(double scale);
102 
103  /* Start playback of the bag file using the parameters previously
104  set */
105  void start_play();
106 
107  /* Get the current time of the playback */
109 
110  // Destructor
111  virtual ~BagPlayer();
112 
113 
114  // The bag file interface loaded in the constructor.
115  Bag bag;
116 
117 private:
119 
120  std::map<std::string, BagCallback *> cbs_;
124  double playback_speed_;
126 };
127 
128 template<class T>
130  typename BagCallbackT<T>::Callback cb) {
131  cbs_[topic] = new BagCallbackT<T>(cb);
132 }
133 
134 }
135 
136 #endif
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::Bag
Definition: bag.h:111
rosbag::BagCallback::~BagCallback
virtual ~BagCallback()
Definition: bag_player.h:114
rosbag::BagPlayer::BagPlayer
BagPlayer(const std::string &filename)
Definition: bag_player.cpp:6
rosbag::BagCallbackT::BagCallbackT
BagCallbackT(Callback cb)
Definition: bag_player.h:93
rosbag::BagPlayer::get_time
rs2rosinternal::Time get_time()
Definition: bag_player.cpp:20
string
GLsizei const GLchar *const * string
Definition: glad/glad/glad.h:2861
void
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
rosbag::BagPlayer::cbs_
std::map< std::string, BagCallback * > cbs_
Definition: bag_player.h:152
rosbag::BagCallback::call
virtual void call(MessageInstance m)=0
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
rosbag::BagCallbackT::Callback
std::function< void(const std::shared_ptr< const T > &)> Callback
Definition: bag_player.h:91
f
GLdouble f
Definition: glad/glad/glad.h:1517
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::BagPlayer::play_start_
rs2rosinternal::Time play_start_
Definition: bag_player.h:157
rosbag::BagCallbackT::call
void call(MessageInstance m)
Definition: bag_player.h:97
start
GLuint start
Definition: glad/glad/glad.h:2395
bag.h
test-projection-from-recording.filename
filename
Definition: test-projection-from-recording.py:15
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
view.h
rosbag::BagPlayer::register_callback
void register_callback(const std::string &topic, typename BagCallbackT< T >::Callback f)
Definition: bag_player.h:161
rosbag
Definition: bag.h:61
rosbag::BagCallbackT::cb_
Callback cb_
Definition: bag_player.h:102
rosbag::BagCallbackT
Definition: bag_player.h:88
rosbag::BagPlayer::set_playback_speed
void set_playback_speed(double scale)
Definition: bag_player.cpp:32
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
rosbag::BagPlayer::~BagPlayer
virtual ~BagPlayer()
Definition: bag_player.cpp:16


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Mon Apr 22 2024 02:12:55