player.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of Willow Garage, Inc. nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 ********************************************************************/
00034 
00035 #ifndef ROSBAG_PLAYER_H
00036 #define ROSBAG_PLAYER_H
00037 
00038 #include <sys/stat.h>
00039 #include <termios.h>
00040 #include <time.h>
00041 #include <unistd.h>
00042 
00043 #include <queue>
00044 #include <string>
00045 
00046 #include <ros/ros.h>
00047 #include <ros/time.h>
00048 
00049 #include "rosbag/bag.h"
00050 
00051 #include "rosbag/time_translator.h"
00052 
00053 namespace rosbag {
00054 
00055 struct PlayerOptions
00056 {
00057     PlayerOptions();
00058 
00059     void check();
00060 
00061     bool     quiet;
00062     bool     start_paused;
00063     bool     at_once;
00064     bool     bag_time;
00065     double   bag_time_frequency;
00066     double   time_scale;
00067     int      queue_size;
00068     ros::WallDuration advertise_sleep;
00069     bool     try_future;
00070     bool     has_time;
00071     bool     loop;
00072     float    time;
00073     bool     keep_alive;
00074     ros::Duration skip_empty;
00075 
00076     std::vector<std::string> bags;
00077     std::vector<std::string> topics;
00078 };
00079 
00080 
00082 class TimePublisher {
00083 public:
00087     TimePublisher();
00088 
00089     void setPublishFrequency(double publish_frequency);
00090     
00091     void setTimeScale(double time_scale);
00092 
00094     void setHorizon(const ros::Time& horizon);
00095 
00097     void setWCHorizon(const ros::WallTime& horizon);
00098 
00100     void setTime(const ros::Time& time);
00101 
00103     ros::Time const& getTime() const;
00104 
00109     void runClock(const ros::WallDuration& duration);
00110 
00112     void runStalledClock(const ros::WallDuration& duration);
00113 
00115     void stepClock();
00116 
00117     bool horizonReached();
00118 
00119 private:
00120     bool do_publish_;
00121     
00122     double publish_frequency_;
00123     double time_scale_;
00124     
00125     ros::NodeHandle node_handle_;
00126     ros::Publisher time_pub_;
00127     
00128     ros::WallDuration wall_step_;
00129     
00130     ros::WallTime next_pub_;
00131 
00132     ros::WallTime wc_horizon_;
00133     ros::Time horizon_;
00134     ros::Time current_;
00135 };
00136 
00137 
00139 
00143 class Player
00144 {
00145 public:
00146     Player(PlayerOptions const& options);
00147     ~Player();
00148 
00149     void publish();
00150 
00151 private:
00152     char readCharFromStdin();
00153     void setupTerminal();
00154     void restoreTerminal();
00155 
00156     void doPublish(rosbag::MessageInstance const& m);
00157 
00158     void doKeepAlive();
00159 
00160     void printTime();
00161 
00162 
00163 private:
00164 
00165     PlayerOptions options_;
00166 
00167     ros::NodeHandle node_handle_;
00168 
00169     bool paused_;
00170 
00171     ros::WallTime paused_time_;
00172 
00173     std::vector<boost::shared_ptr<Bag> >  bags_;
00174     std::map<std::string, ros::Publisher> publishers_;
00175 
00176     // Terminal
00177     bool    terminal_modified_;
00178     termios orig_flags_;
00179     fd_set  stdin_fdset_;
00180     int     maxfd_;
00181 
00182     TimeTranslator time_translator_;
00183     TimePublisher time_publisher_;
00184 
00185     ros::Time start_time_;
00186     ros::Duration bag_length_;
00187 };
00188 
00189 
00190 } // namespace rosbag
00191 
00192 #endif


rosbag
Author(s): Tim Field (tfield@willowgarage.com), Jeremy Leibs (leibs@willowgarage.com), and James Bowman (jamesb@willowgarage.com)
autogenerated on Sat Dec 28 2013 17:43:05