$search
00001 /* 00002 * split_bag.cpp 00003 * 00004 * Created on: Oct 19, 2012 00005 * Author: jelfring 00006 */ 00007 00008 00009 // ROS 00010 #include <ros/ros.h> 00011 00012 // OpenCv 00013 #include "cv.h" 00014 #include "highgui.h" 00015 00016 // For transforming ROS/OpenCV images 00017 #include <cv_bridge/cv_bridge.h> 00018 #include <sensor_msgs/image_encodings.h> 00019 00020 // Messages 00021 #include "sensor_msgs/Image.h" 00022 #include "tf/tfMessage.h" 00023 #include "wire_msgs/WorldEvidence.h" 00024 #include "sensor_msgs/CameraInfo.h" 00025 #include <std_msgs/Bool.h> 00026 #include <std_msgs/Float64.h> 00027 00028 // Bag files 00029 #include <rosbag/bag.h> 00030 #include <rosbag/view.h> 00031 00032 #include <fstream> 00033 00034 // Boost 00035 #include <boost/foreach.hpp> 00036 #include <boost/filesystem.hpp> 00037 #include "boost/format.hpp" 00038 00039 using namespace std; 00040 00041 int main( int argc, char** argv ) { 00042 00043 if (argc != 4) { 00044 std::cout << "Need 3 arguments: <INPUT.bag> <FRAME_RATE> <OUTPUT>" << std::endl; 00045 exit(-1); 00046 } 00047 00048 // Default values 00049 std::string bag_in_name = argv[1]; 00050 int video_frame_rate = atoi(argv[2]); 00051 std::string bag_out_name = std::string(argv[3]) + ".bag"; 00052 std::string yaml_name = std::string(argv[3]) + ".yaml"; 00053 00054 // Check input 00055 if (bag_in_name == "") { 00056 ROS_ERROR("No input bag file defined!"); 00057 return -1; 00058 } 00059 if (video_frame_rate <= 0) { 00060 ROS_ERROR("No video frame rate defined!"); 00061 return -1; 00062 } 00063 00064 // Video writers 00065 map<std::string, cv::VideoWriter*> topic_to_video_writer; 00066 map<std::string, std::string> topic_to_video_filename; 00067 00068 // Load input bag file 00069 rosbag::Bag bag; 00070 bag.open(bag_in_name, rosbag::bagmode::Read); 00071 ROS_INFO("Opened %s", bag_in_name.c_str()); 00072 00073 // Create output bag file 00074 rosbag::Bag bag_out; 00075 bag_out.open(bag_out_name, rosbag::bagmode::Write); 00076 ROS_INFO("Created %s", bag_out_name.c_str()); 00077 00078 // Get topics 00079 rosbag::View view(bag); 00080 00081 // Loop over messages 00082 BOOST_FOREACH(rosbag::MessageInstance const m, view) { 00083 00084 // Get data 00085 sensor_msgs::ImageConstPtr image_msg = m.instantiate<sensor_msgs::Image>(); 00086 tf::tfMessageConstPtr transform = m.instantiate<tf::tfMessage>(); 00087 wire_msgs::WorldEvidenceConstPtr evidence = m.instantiate<wire_msgs::WorldEvidence>(); 00088 sensor_msgs::CameraInfoConstPtr cam_info = m.instantiate<sensor_msgs::CameraInfo>(); 00089 00090 // Images to video 00091 if (image_msg != NULL) { 00092 00093 cv::Mat image; 00094 00095 if (image_msg->encoding == "32FC1") { // depth image 00096 cv_bridge::CvImagePtr depth_image_ptr; 00097 try { 00098 depth_image_ptr = cv_bridge::toCvCopy(image_msg); 00099 } catch (cv_bridge::Exception& e) { 00100 ROS_ERROR("cv_bridge exception: %s", e.what()); 00101 } 00102 00103 // find max depth 00104 float max_depth = 0; 00105 for(int y = 0; y < depth_image_ptr->image.rows; y++) { 00106 for(int x = 0; x < depth_image_ptr->image.cols; x++) { 00107 float distance = depth_image_ptr->image.at<float>(y, x); 00108 if (distance == distance) { // exclude NaN 00109 max_depth = max(distance, max_depth); 00110 } 00111 } 00112 } 00113 00114 image = cv::Mat(depth_image_ptr->image.rows, depth_image_ptr->image.cols, CV_8UC3); 00115 00116 for(int y = 0; y < depth_image_ptr->image.rows; y++) { 00117 for(int x = 0; x < depth_image_ptr->image.cols; x++) { 00118 float distance = depth_image_ptr->image.at<float>(y, x); 00119 unsigned int dist_clr = (unsigned int)(distance / max_depth * 255); 00120 image.at<cv::Vec3b>(y, x) = cv::Vec3b(dist_clr, dist_clr, dist_clr); 00121 } 00122 } 00123 00124 std_msgs::Float64 max_depth_msg; 00125 max_depth_msg.data = max_depth; 00126 bag_out.write(m.getTopic() +"/_trigger", image_msg->header.stamp, max_depth_msg); 00127 00128 } else if (image_msg->encoding == "rgb8" || image_msg->encoding == "bgr8" ) { // color image 00129 // Convert color OpenCV image 00130 cv_bridge::CvImageConstPtr color_image_ptr; 00131 try { 00132 color_image_ptr = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::BGR8); 00133 } catch (cv_bridge::Exception& e) { 00134 ROS_ERROR("cv_bridge exception: %s", e.what()); 00135 } 00136 00137 image = color_image_ptr->image; 00138 00139 std_msgs::Bool b; 00140 b.data = true; 00141 bag_out.write(m.getTopic() +"/_trigger", image_msg->header.stamp, b); 00142 } else { 00143 ROS_ERROR("Unknown image encoding: %s", image_msg->encoding.c_str()); 00144 } 00145 00146 //cv::imshow(m.getTopic(), image); 00147 //cv::waitKey(1); 00148 00149 cv::VideoWriter* video_writer; 00150 map<std::string, cv::VideoWriter*>::iterator it_video_writer = topic_to_video_writer.find(m.getTopic()); 00151 if (it_video_writer != topic_to_video_writer.end()) { 00152 video_writer = it_video_writer->second; 00153 } else { 00154 stringstream s_filename; 00155 s_filename << std::string(argv[3]) << "_" << topic_to_video_writer.size() << ".avi"; 00156 topic_to_video_filename[m.getTopic()] = s_filename.str(); 00157 00158 const cv::Size2i video_size(image.cols, image.rows); 00159 video_writer = new cv::VideoWriter(s_filename.str(), CV_FOURCC('D','I','V','X'), video_frame_rate, video_size); 00160 if (video_writer->isOpened()) { 00161 ROS_INFO("Created video writer for topic %s (output file %s)", m.getTopic().c_str(), s_filename.str().c_str()); 00162 } else { 00163 ROS_ERROR("Unable to create video writer for topic %s (output file %s)", m.getTopic().c_str(), s_filename.str().c_str()); 00164 exit(-1); 00165 } 00166 topic_to_video_writer[m.getTopic()] = video_writer; 00167 } 00168 00169 // Add image to video 00170 video_writer->write(image); 00171 } 00172 00173 // Tfs to bag 00174 if (transform) { 00175 bag_out.write(m.getTopic(), m.getTime(), transform); 00176 } 00177 00178 // World evidence to bag 00179 if (evidence) { 00180 bag_out.write(m.getTopic(), m.getTime(), evidence); 00181 } 00182 00183 if (cam_info) { 00184 bag_out.write(m.getTopic(), m.getTime(), cam_info); 00185 } 00186 } 00187 00188 bag.close(); 00189 bag_out.close(); 00190 ROS_INFO("Finished bag file"); 00191 00192 std::ofstream fout(yaml_name.c_str()); 00193 fout << "bag: " << bag_out_name << std::endl; 00194 00195 if (!topic_to_video_writer.empty()) { 00196 fout << "videos:" << std::endl; 00197 } 00198 00199 for(map<std::string, cv::VideoWriter*>::iterator it_vw = topic_to_video_writer.begin(); it_vw != topic_to_video_writer.end(); ++it_vw) { 00200 fout << " - {file: \"" << topic_to_video_filename[it_vw->first] << "\", topic: \"" << it_vw->first << "\"}" << std::endl; 00201 } 00202 00203 return 0; 00204 00205 }