$search
00001 /* 00002 * merge_video_bag.cpp 00003 * 00004 * Created on: Oct 19, 2012 00005 * Author: jelfring 00006 */ 00007 00008 // ROS 00009 #include <ros/ros.h> 00010 00011 // OpenCv 00012 #include "cv.h" 00013 #include "highgui.h" 00014 00015 // For transforming ROS/OpenCV images 00016 #include <cv_bridge/cv_bridge.h> 00017 #include <sensor_msgs/image_encodings.h> 00018 00019 // Messages 00020 #include "sensor_msgs/Image.h" 00021 #include "tf/tfMessage.h" 00022 #include "wire_msgs/WorldEvidence.h" 00023 #include "sensor_msgs/CameraInfo.h" 00024 #include <std_msgs/Bool.h> 00025 #include <std_msgs/Float64.h> 00026 00027 // Bag files 00028 #include <rosbag/bag.h> 00029 #include <rosbag/view.h> 00030 00031 #include "yaml-cpp/yaml.h" 00032 00033 #include <fstream> 00034 00035 // Boost 00036 #include <boost/foreach.hpp> 00037 #include <boost/filesystem.hpp> 00038 #include "boost/format.hpp" 00039 00040 int main( int argc, char** argv ) { 00041 00042 if (argc < 2 || argc > 3) { 00043 std::cout << "Please give yaml file as argument." << std::endl; 00044 exit(-1); 00045 } 00046 00047 std::string filename = argv[1]; 00048 00049 std::cout << filename << std::endl; 00050 00051 std::ifstream fin(filename.c_str()); 00052 if (fin.fail()) { 00053 ROS_ERROR("Could not open %s.", filename.c_str()); 00054 exit(-1); 00055 } 00056 00057 // Default values 00058 std::string bag_in_name = ""; 00059 std::string bag_out_name = "final.bag"; 00060 if (argc == 3) { 00061 bag_out_name = argv[2]; 00062 } 00063 00064 // load file names from yaml file 00065 YAML::Parser parser(fin); 00066 YAML::Node doc; 00067 parser.GetNextDocument(doc); 00068 try { 00069 doc["bag"] >> bag_in_name; 00070 } catch (YAML::InvalidScalar) { 00071 ROS_ERROR("The input file does not contain a bag tag or is invalid."); 00072 exit(-1); 00073 } 00074 00075 const YAML::Node* n_videos = doc.FindValue("videos"); 00076 if (!n_videos) { 00077 ROS_ERROR("The input file does not contain a video tag or is invalid."); 00078 exit(-1); 00079 } 00080 00081 std::map<std::string, cv::VideoCapture*> topic_to_video_capture; 00082 00083 for (YAML::Iterator it_n_video = n_videos->begin(); it_n_video != n_videos->end(); ++it_n_video) { 00084 std::string video_filename; 00085 std::string video_topic; 00086 00087 try { 00088 (*it_n_video)["file"] >> video_filename; 00089 (*it_n_video)["topic"] >> video_topic; 00090 } catch (YAML::InvalidScalar) { 00091 ROS_ERROR("Invalid video specification: should contain 'file' and 'topic'."); 00092 exit(-1); 00093 } 00094 00095 cv::VideoCapture* video_capture = new cv::VideoCapture(video_filename); 00096 00097 if (!video_capture->isOpened()) { 00098 ROS_ERROR("Unable to open video: %s", video_filename.c_str()); 00099 return 0; 00100 } else ROS_INFO("Opened video %s for topic %s", video_filename.c_str(), video_topic.c_str()); 00101 00102 topic_to_video_capture[video_topic] = video_capture; 00103 } 00104 00105 // Check input 00106 if (bag_in_name == "") { 00107 ROS_ERROR("No input bag file defined!"); 00108 return -1; 00109 } 00110 00111 // Load input bag file 00112 rosbag::Bag bag_in; 00113 bag_in.open(bag_in_name, rosbag::bagmode::Read); 00114 ROS_INFO("Opened %s", bag_in_name.c_str()); 00115 00116 // Create output bag file 00117 rosbag::Bag bag_out; 00118 bag_out.open(bag_out_name, rosbag::bagmode::Write); 00119 ROS_INFO("Created %s", bag_out_name.c_str()); 00120 00121 // Get topics and time from input bag file 00122 rosbag::View view(bag_in); 00123 00124 cv::Mat rgb_frame; 00125 cv_bridge::CvImagePtr rgb_img_ptr(new cv_bridge::CvImage); 00126 sensor_msgs::ImagePtr rgb_img; 00127 00128 cv::Mat depth_frame; 00129 cv_bridge::CvImagePtr depth_img_ptr(new cv_bridge::CvImage); 00130 sensor_msgs::ImagePtr depth_img; 00131 00132 // Loop over messages and write topics to output bag file 00133 BOOST_FOREACH(rosbag::MessageInstance const m, view) { 00134 00135 // Get data 00136 tf::tfMessageConstPtr transform = m.instantiate<tf::tfMessage>(); 00137 wire_msgs::WorldEvidenceConstPtr evidence = m.instantiate<wire_msgs::WorldEvidence>(); 00138 std_msgs::BoolConstPtr img_rgb_trigger = m.instantiate<std_msgs::Bool>(); 00139 std_msgs::Float64ConstPtr img_depth_trigger = m.instantiate<std_msgs::Float64>(); 00140 sensor_msgs::CameraInfoConstPtr cam_info = m.instantiate<sensor_msgs::CameraInfo>(); 00141 00142 // Tfs 00143 if (transform) { 00144 bag_out.write(m.getTopic(), m.getTime(), transform); 00145 } 00146 00147 // World evidence 00148 if (evidence) { 00149 bag_out.write(m.getTopic(), m.getTime(), evidence); 00150 } 00151 00152 if (cam_info) { 00153 bag_out.write(m.getTopic(), m.getTime(), cam_info); 00154 } 00155 00156 if (m.getTopic().find("/_trigger") != std::string::npos) { 00157 std::string image_topic = m.getTopic(); 00158 image_topic.replace(image_topic.end() - 9, image_topic.end(), ""); 00159 00160 std::map<std::string, cv::VideoCapture*>::iterator it_vc = topic_to_video_capture.find(image_topic); 00161 if (it_vc == topic_to_video_capture.end()) { 00162 ROS_ERROR("Image topic %s was not specified in YAML file.", image_topic.c_str()); 00163 exit(-1); 00164 } 00165 cv::VideoCapture* video_capture = it_vc->second; 00166 00167 if (img_rgb_trigger) { 00168 (*video_capture) >> rgb_frame; 00169 00170 if( rgb_frame.empty()) { 00171 ROS_ERROR("Unexpected end of video!"); 00172 } 00173 00174 // Add image, frame and encoding to the image message 00175 rgb_img_ptr->image = rgb_frame; 00176 rgb_img = rgb_img_ptr->toImageMsg(); 00177 rgb_img->header.frame_id = "/openni_rgb_optical_frame"; 00178 rgb_img->header.stamp = m.getTime(); 00179 rgb_img->encoding = "bgr8"; 00180 00181 // Write to bag file 00182 bag_out.write(image_topic, m.getTime(), rgb_img); 00183 } else if (img_depth_trigger) { 00184 (*video_capture) >> depth_frame; 00185 00186 if(depth_frame.empty()) { 00187 ROS_ERROR("Unexpected end of depth video!"); 00188 } 00189 00190 cv::Mat depth_mat(depth_frame.rows, depth_frame.cols, CV_32FC1); 00191 00192 for(int y = 0; y < depth_frame.rows; y++) { 00193 for(int x = 0; x < depth_frame.cols; x++) { 00194 unsigned char dist_char = depth_frame.at<cv::Vec3b>(y, x)[0]; 00195 float distance = (float)dist_char / 255 * img_depth_trigger->data; 00196 depth_mat.at<float>(y, x) = distance; 00197 } 00198 } 00199 00200 // Add image, frame and encoding to the image message 00201 depth_img_ptr->image = depth_mat; 00202 depth_img = depth_img_ptr->toImageMsg(); 00203 depth_img->header.frame_id = "/openni_rgb_optical_frame"; 00204 depth_img->header.stamp = m.getTime(); 00205 depth_img->encoding = "32FC1"; 00206 00207 // Write to bag file 00208 bag_out.write(image_topic, m.getTime(), depth_img); 00209 } else { 00210 ROS_ERROR("Unknown trigger topic: %s", m.getTopic().c_str()); 00211 } 00212 } 00213 } 00214 00215 for (std::map<std::string, cv::VideoCapture*>::iterator it_vc = topic_to_video_capture.begin(); it_vc != topic_to_video_capture.end(); ++it_vc) { 00216 delete it_vc->second; 00217 } 00218 00219 bag_in.close(); 00220 bag_out.close(); 00221 ROS_INFO("Finished bag file"); 00222 00223 return 0; 00224 00225 }