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 namespace rosbag
42 {
43 
44 
45 // A helper struct
47 {
48  virtual ~BagCallback() {};
49  virtual void call(MessageInstance m) = 0;
50 };
51 
52 // A helper class for the callbacks
53 template<class T>
54 class BagCallbackT : public BagCallback
55 {
56 public:
57  typedef boost::function<void (const boost::shared_ptr<const T>&)> Callback;
58 
60  cb_(cb)
61  {}
62 
64  cb_(m.instantiate<T>());
65  }
66 
67 private:
69 };
70 
71 template<>
73 {
74 public:
75  typedef boost::function<void (const MessageInstance&)> Callback;
76 
77  BagCallbackT(Callback cb) :
78  cb_(cb)
79  {}
80 
82  cb_(m);
83  }
84 
85 private:
86  Callback cb_;
87 };
88 
89 
90 /* A class for playing back bag files at an API level. It supports
91  relatime, as well as accelerated and slowed playback. */
93 {
94 public:
95  /* Constructor expecting the filename of a bag */
96  BagPlayer(const std::string &filename);
97 
98  /* Register a callback for a specific topic and type */
99  template<class T>
100  void register_callback(const std::string &topic,
101  typename BagCallbackT<T>::Callback f);
102 
103  /* Unregister a callback for a topic already registered */
104  void unregister_callback(const std::string &topic);
105 
106  /* Set the time in the bag to start.
107  * Default is the first message */
108  void set_start(const ros::Time &start);
109 
110  /* Set the time in the bag to stop.
111  * Default is the last message */
112  void set_end(const ros::Time &end);
113 
114  /* Set the speed to playback. 1.0 is the default.
115  * 2.0 would be twice as fast, 0.5 is half realtime. */
116  void set_playback_speed(double scale);
117 
118  /* Start playback of the bag file using the parameters previously
119  set */
120  void start_play();
121 
122  /* Get the current time of the playback */
123  ros::Time get_time();
124 
125  // Destructor
126  virtual ~BagPlayer();
127 
128 
129  // The bag file interface loaded in the constructor.
131 
132 private:
133  ros::Time real_time(const ros::Time &msg_time);
134 
135  std::map<std::string, boost::shared_ptr<BagCallback> > cbs_;
141 };
142 
143 template<class T>
144 void BagPlayer::register_callback(const std::string &topic,
145  typename BagCallbackT<T>::Callback cb) {
146  cbs_[topic] = boost::make_shared<BagCallbackT<T> >(cb);
147 }
148 
149 }
150 
151 #endif
virtual void call(MessageInstance m)=0
#define ROSBAG_STORAGE_DECL
Definition: macros.h:50
boost::function< void(const boost::shared_ptr< const T > &)> Callback
Definition: bag_player.h:57
ROSCPP_DECL void start()
f
std::map< std::string, boost::shared_ptr< BagCallback > > cbs_
Definition: bag_player.h:135
boost::function< void(const MessageInstance &)> Callback
Definition: bag_player.h:75
BagCallbackT(Callback cb)
Definition: bag_player.h:59
ros::Time play_start_
Definition: bag_player.h:140
ros::Time bag_start_
Definition: bag_player.h:136
void register_callback(const std::string &topic, typename BagCallbackT< T >::Callback f)
Definition: bag_player.h:144
void call(MessageInstance m)
Definition: bag_player.h:63
ros::Time last_message_time_
Definition: bag_player.h:138
A class pointing into a bag file.
void call(MessageInstance m)
Definition: bag_player.h:81
virtual ~BagCallback()
Definition: bag_player.h:48
boost::shared_ptr< T > instantiate() const
Templated call to instantiate a message.
double playback_speed_
Definition: bag_player.h:139
ros::Time bag_end_
Definition: bag_player.h:137


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