$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2010, Robert Bosch LLC. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Robert Bosch nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * Author(s): Ralf Kemp, revised to electric Sarah Osentoski 00036 *********************************************************************/ 00037 00038 #ifndef ROSBAG_RECORDER_H 00039 #define ROSBAG_RECORDER_H 00040 00041 #include <sys/stat.h> 00042 #include <termios.h> 00043 #include <time.h> 00044 #include <unistd.h> 00045 00046 #include <queue> 00047 #include <string> 00048 #include <vector> 00049 00050 #include <boost/thread/condition.hpp> 00051 #include <boost/thread/mutex.hpp> 00052 #include <boost/thread.hpp> 00053 #include <boost/regex.hpp> 00054 #include <boost/shared_ptr.hpp> 00055 00056 #include <ros/ros.h> 00057 #include <ros/time.h> 00058 00059 #include <std_msgs/Empty.h> 00060 #include <topic_tools/shape_shifter.h> 00061 00062 #include "rosbag/bag.h" 00063 #include "rosbag/stream.h" 00064 00065 namespace rosbag { 00066 00067 class OutgoingMessage 00068 { 00069 public: 00070 OutgoingMessage(std::string const& _topic, topic_tools::ShapeShifter::ConstPtr _msg, boost::shared_ptr<ros::M_string> _connection_header, ros::Time _time); 00071 00072 std::string topic; 00073 topic_tools::ShapeShifter::ConstPtr msg; 00074 boost::shared_ptr<ros::M_string> connection_header; 00075 ros::Time time; 00076 }; 00077 00078 class OutgoingQueue 00079 { 00080 public: 00081 OutgoingQueue(std::string const& _filename, std::queue<OutgoingMessage>* _queue, ros::Time _time); 00082 00083 std::string filename; 00084 std::queue<OutgoingMessage>* queue; 00085 ros::Time time; 00086 }; 00087 00088 struct RecorderOptions 00089 { 00090 RecorderOptions(); 00091 00092 bool trigger; 00093 bool record_all; 00094 bool regex; 00095 bool do_exclude; 00096 bool quiet; 00097 bool append_date; 00098 bool snapshot; 00099 bool verbose; 00100 CompressionType compression; 00101 std::string prefix; 00102 std::string name; 00103 boost::regex exclude_regex; 00104 uint32_t buffer_size; 00105 uint32_t limit; 00106 bool split; 00107 uint32_t max_size; 00108 ros::Duration max_duration; 00109 std::string node; 00110 00111 std::vector<std::string> topics; 00112 }; 00113 00114 class Recorder 00115 { 00116 public: 00117 Recorder(RecorderOptions const& options); 00118 Recorder(); 00119 00120 00121 void doTrigger(); 00122 00123 bool isSubscribed(std::string const& topic) const; 00124 00125 boost::shared_ptr<ros::Subscriber> subscribe(std::string const& topic); 00126 00127 int run(); 00128 00129 void stop(); //stops recording and closes the bagfile 00130 00131 void upload(); //loads the bagfile up to a predefined destination via scp 00132 00133 void deleteFile(); //deletes the local copy of the bagfile (useful after successful upload) 00134 00135 //need to be public in order to acccess them from the ActionServer 00136 std::string target_filename_; 00137 RecorderOptions options_; 00138 Bag bag_; 00139 00140 private: 00141 void printUsage(); 00142 00143 void updateFilenames(); 00144 void startWriting(); 00145 void stopWriting(); 00146 00147 bool checkLogging(); 00148 bool scheduledCheckDisk(); 00149 bool checkDisk(); 00150 00151 void snapshotTrigger(std_msgs::Empty::ConstPtr trigger); 00152 // void doQueue(topic_tools::ShapeShifter::ConstPtr msg, std::string const& topic, boost::shared_ptr<ros::Subscriber> subscriber, boost::shared_ptr<int> count); 00153 void doQueue(ros::MessageEvent<topic_tools::ShapeShifter const> msg_event, std::string const& topic, boost::shared_ptr<ros::Subscriber> subscriber, boost::shared_ptr<int> count); 00154 void doRecord(); 00155 bool checkSize(); 00156 bool checkDuration(const ros::Time&); 00157 void doRecordSnapshotter(); 00158 void doCheckMaster(ros::TimerEvent const& e, ros::NodeHandle& node_handle); 00159 00160 bool shouldSubscribeToTopic(std::string const& topic, bool from_node = false); 00161 00162 template<class T> 00163 static std::string timeToStr(T ros_t); 00164 00165 private: 00166 00167 boost::thread record_thread; 00168 bool stop_; 00169 std::vector<boost::shared_ptr<ros::Subscriber> > subscriber_handles_; 00170 00171 //Bag bag_; 00172 00173 //std::string target_filename_; 00174 std::string write_filename_; 00175 00176 std::set<std::string> currently_recording_; 00177 int num_subscribers_; 00178 00179 int exit_code_; 00180 00181 boost::condition_variable_any queue_condition_; 00182 boost::mutex queue_mutex_; 00183 std::queue<OutgoingMessage>* queue_; 00184 uint64_t queue_size_; 00185 uint64_t max_queue_size_; 00186 00187 uint64_t split_count_; 00188 00189 std::queue<OutgoingQueue> queue_queue_; 00190 00191 ros::Time last_buffer_warn_; 00192 00193 ros::Time start_time_; 00194 00195 bool writing_enabled_; 00196 boost::mutex check_disk_mutex_; 00197 ros::WallTime check_disk_next_; 00198 ros::WallTime warn_next_; 00199 }; 00200 00201 } // namespace rosbag 00202 00203 #endif