35 #ifndef ROSBAG_PLAYER_H 36 #define ROSBAG_PLAYER_H 39 #if !defined(_MSC_VER) 50 #include <std_srvs/SetBool.h> 99 std::vector<std::string>
bags;
113 void setPublishFrequency(
double publish_frequency);
115 void setTimeScale(
double time_scale);
118 void setHorizon(
const ros::Time& horizon);
141 bool horizonReached();
176 int readCharFromStdin();
177 void setupTerminal();
178 void restoreTerminal();
188 bool pauseCallback(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res);
190 void processPause(
const bool paused,
ros::WallTime &horizon);
192 void waitForSubscribers()
const;
217 std::vector<boost::shared_ptr<Bag> >
bags_;
222 #if defined(_MSC_VER)
bool wait_for_subscribers
TimeTranslator time_translator_
std::string rate_control_topic
std::vector< std::string > topics
bool requested_pause_state_
std::vector< std::string > pause_topics
ros::WallDuration wall_step_
std::vector< std::string > bags
ros::WallTime wc_horizon_
Helper class for translating between two times.
float rate_control_max_delay
ros::WallDuration advertise_sleep
double bag_time_frequency
ros::NodeHandle node_handle_
double publish_frequency_
ros::Subscriber rate_control_sub_
std::vector< boost::shared_ptr< Bag > > bags_
ros::ServiceServer pause_service_
ros::WallTime paused_time_
PRIVATE. Player class to abstract the interface to the player.
ros::NodeHandle node_handle_
PRIVATE. A helper class to track relevant state for publishing time.
ros::Duration bag_length_
ros::AdvertiseOptions createAdvertiseOptions(MessageInstance const &msg, uint32_t queue_size, const std::string &prefix="")
Helper function to create AdvertiseOptions from a MessageInstance.
ros::Time last_rate_control_
bool pause_change_requested_
std::map< std::string, ros::Publisher > PublisherMap
TimePublisher time_publisher_