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


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:34:21