00001 #include "rosbag/bag_player.h" 00002 00003 #define foreach BOOST_FOREACH 00004 00005 namespace rosbag 00006 { 00007 00008 BagPlayer::BagPlayer(const std::string &fname) throw(BagException) { 00009 bag.open(fname, rosbag::bagmode::Read); 00010 ros::Time::init(); 00011 View v(bag); 00012 bag_start_ = v.getBeginTime(); 00013 bag_end_ = v.getEndTime(); 00014 last_message_time_ = ros::Time(0); 00015 playback_speed_ = 1.0; 00016 } 00017 00018 BagPlayer::~BagPlayer() { 00019 bag.close(); 00020 } 00021 00022 ros::Time BagPlayer::get_time() { 00023 return last_message_time_; 00024 } 00025 00026 void BagPlayer::set_start(const ros::Time &start) { 00027 bag_start_ = start; 00028 } 00029 00030 void BagPlayer::set_end(const ros::Time &end) { 00031 bag_end_ = end; 00032 } 00033 00034 void BagPlayer::set_playback_speed(double scale) { 00035 if (scale > 0.0) 00036 playback_speed_ = scale; 00037 } 00038 00039 ros::Time BagPlayer::real_time(const ros::Time &msg_time) { 00040 return play_start_ + (msg_time - bag_start_) * (1 / playback_speed_); 00041 } 00042 00043 void BagPlayer::start_play() { 00044 00045 std::vector<std::string> topics; 00046 std::pair<std::string, BagCallback *> cb; 00047 foreach(cb, cbs_) 00048 topics.push_back(cb.first); 00049 00050 View view(bag, TopicQuery(topics), bag_start_, bag_end_); 00051 play_start_ = ros::Time::now(); 00052 00053 foreach(MessageInstance const m, view) 00054 { 00055 if (cbs_.find(m.getTopic()) == cbs_.end()) 00056 continue; 00057 00058 ros::Time::sleepUntil(real_time(m.getTime())); 00059 00060 last_message_time_ = m.getTime(); /* this is the recorded time */ 00061 cbs_[m.getTopic()]->call(m); 00062 } 00063 } 00064 00065 void BagPlayer::unregister_callback(const std::string &topic) { 00066 delete cbs_[topic]; 00067 cbs_.erase(topic); 00068 } 00069 00070 } 00071