player.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
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_PLAYER_H
36 #define ROSBAG_PLAYER_H
37 
38 #include <sys/stat.h>
39 #if !defined(_MSC_VER)
40  #include <termios.h>
41  #include <unistd.h>
42 #endif
43 #include <time.h>
44 
45 #include <queue>
46 #include <string>
47 
48 #include <ros/ros.h>
49 #include <ros/time.h>
50 #include <std_srvs/SetBool.h>
51 
52 #include "rosbag/bag.h"
53 
55 
56 #include "rosbag/time_translator.h"
57 #include "rosbag/macros.h"
58 
59 namespace rosbag {
60 
62 
67 ros::AdvertiseOptions createAdvertiseOptions(MessageInstance const& msg, uint32_t queue_size, const std::string& prefix = "");
68 
69 ROSBAG_DECL ros::AdvertiseOptions createAdvertiseOptions(const ConnectionInfo* c, uint32_t queue_size, const std::string& prefix = "");
70 
71 
73 {
74  PlayerOptions();
75 
76  void check();
77 
78  std::string prefix;
79  bool quiet;
81  bool at_once;
82  bool bag_time;
84  double time_scale;
87  bool try_future;
88  bool has_time;
89  bool loop;
90  float time;
92  float duration;
93  bool keep_alive;
95  std::string rate_control_topic;
98 
99  std::vector<std::string> bags;
100  std::vector<std::string> topics;
101  std::vector<std::string> pause_topics;
102 };
103 
104 
107 public:
111  TimePublisher();
112 
113  void setPublishFrequency(double publish_frequency);
114 
115  void setTimeScale(double time_scale);
116 
118  void setHorizon(const ros::Time& horizon);
119 
121  void setWCHorizon(const ros::WallTime& horizon);
122 
124  void setTime(const ros::Time& time);
125 
127  ros::Time const& getTime() const;
128 
133  void runClock(const ros::WallDuration& duration);
134 
136  void runStalledClock(const ros::WallDuration& duration);
137 
139  void stepClock();
140 
141  bool horizonReached();
142 
143 private:
145 
147  double time_scale_;
148 
151 
153 
155 
159 };
160 
161 
163 
168 {
169 public:
170  Player(PlayerOptions const& options);
171  ~Player();
172 
173  void publish();
174 
175 private:
176  int readCharFromStdin();
177  void setupTerminal();
178  void restoreTerminal();
179 
180  void updateRateTopicTime(const ros::MessageEvent<topic_tools::ShapeShifter const>& msg_event);
181 
182  void doPublish(rosbag::MessageInstance const& m);
183 
184  void doKeepAlive();
185 
186  void printTime();
187 
188  bool pauseCallback(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res);
189 
190  void processPause(const bool paused, ros::WallTime &horizon);
191 
192  void waitForSubscribers() const;
193 
194 private:
195  typedef std::map<std::string, ros::Publisher> PublisherMap;
196 
198 
200 
202 
203  bool paused_;
204  bool delayed_;
205 
207 
209 
211 
214 
216 
217  std::vector<boost::shared_ptr<Bag> > bags_;
218  PublisherMap publishers_;
219 
220  // Terminal
222 #if defined(_MSC_VER)
223  HANDLE input_handle;
224  DWORD stdin_set;
225 #else
226  termios orig_flags_;
227  fd_set stdin_fdset_;
228 #endif
229  int maxfd_;
230 
233 
236 };
237 
238 
239 } // namespace rosbag
240 
241 #endif
termios orig_flags_
Definition: player.h:226
ROSCPP_DECL bool check()
bool wait_for_subscribers
Definition: player.h:94
ros::WallTime next_pub_
Definition: player.h:154
TimeTranslator time_translator_
Definition: player.h:231
std::string rate_control_topic
Definition: player.h:95
PlayerOptions options_
Definition: player.h:197
std::vector< std::string > topics
Definition: player.h:100
bool requested_pause_state_
Definition: player.h:210
std::vector< std::string > pause_topics
Definition: player.h:101
ros::WallDuration wall_step_
Definition: player.h:152
ros::Publisher time_pub_
Definition: player.h:150
std::string prefix
Definition: player.h:78
std::vector< std::string > bags
Definition: player.h:99
ros::WallTime wc_horizon_
Definition: player.h:156
Helper class for translating between two times.
float rate_control_max_delay
Definition: player.h:96
ros::WallDuration advertise_sleep
Definition: player.h:86
double bag_time_frequency
Definition: player.h:83
#define ROSBAG_DECL
ros::NodeHandle node_handle_
Definition: player.h:199
double publish_frequency_
Definition: player.h:146
ros::Time horizon_
Definition: player.h:157
ros::Subscriber rate_control_sub_
Definition: player.h:212
bool paused_
Definition: player.h:203
std::vector< boost::shared_ptr< Bag > > bags_
Definition: player.h:217
ros::ServiceServer pause_service_
Definition: player.h:201
bool delayed_
Definition: player.h:204
ros::WallTime paused_time_
Definition: player.h:215
bool pause_for_topics_
Definition: player.h:206
fd_set stdin_fdset_
Definition: player.h:227
bool terminal_modified_
Definition: player.h:221
PRIVATE. Player class to abstract the interface to the player.
Definition: player.h:167
ros::NodeHandle node_handle_
Definition: player.h:149
PRIVATE. A helper class to track relevant state for publishing time.
Definition: player.h:106
ros::Duration bag_length_
Definition: player.h:235
ros::AdvertiseOptions createAdvertiseOptions(MessageInstance const &msg, uint32_t queue_size, const std::string &prefix="")
Helper function to create AdvertiseOptions from a MessageInstance.
Definition: player.cpp:67
ros::Time last_rate_control_
Definition: player.h:213
PublisherMap publishers_
Definition: player.h:218
ros::Duration skip_empty
Definition: player.h:97
bool pause_change_requested_
Definition: player.h:208
ros::Time start_time_
Definition: player.h:234
std::map< std::string, ros::Publisher > PublisherMap
Definition: player.h:195
TimePublisher time_publisher_
Definition: player.h:232
ros::Time current_
Definition: player.h:158


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:53:00