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


rosbag_storage
Author(s):
autogenerated on Sun Feb 3 2019 03:29:47