35 #ifndef ROSBAG_PLAYER_H
36 #define ROSBAG_PLAYER_H
39 #if !defined(_MSC_VER)
52 #include <std_srvs/SetBool.h>
85 double bag_time_frequency;
96 bool wait_for_subscribers;
97 std::string rate_control_topic;
98 float rate_control_max_delay;
101 std::vector<std::string> bags;
102 std::vector<std::string> topics;
103 std::vector<std::string> pause_topics;
115 void setPublishFrequency(
double publish_frequency);
117 void setTimeScale(
double time_scale);
143 bool horizonReached();
148 double publish_frequency_;
178 int readCharFromStdin();
179 void setupTerminal();
180 void restoreTerminal();
192 bool pauseCallback(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res);
194 void processPause(
const bool paused,
ros::WallTime &horizon);
196 void waitForSubscribers()
const;
199 typedef std::map<std::string, ros::Publisher> PublisherMap;
210 bool pause_for_topics_;
212 bool pause_change_requested_;
214 bool requested_pause_state_;
221 std::vector<boost::shared_ptr<Bag> > bags_;
225 bool terminal_modified_;
226 #if defined(_MSC_VER)