$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 <std_msgs/Bool.h> 00022 #include <std_msgs/Float64.h> 00023 #include <rosgraph_msgs/Clock.h> 00024 00025 // Bag files 00026 #include <rosbag/bag.h> 00027 #include <rosbag/view.h> 00028 00029 // YAML 00030 #include "yaml-cpp/yaml.h" 00031 00032 // File operations 00033 #include <fstream> 00034 #include <libgen.h> // for using function 'dirname' 00035 00036 // Boost 00037 #include <boost/foreach.hpp> 00038 #include <boost/filesystem.hpp> 00039 #include "boost/format.hpp" 00040 00041 00042 using namespace std; 00043 00044 int main( int argc, char** argv ) { 00045 00046 if (argc != 2) { 00047 std::cout << "Please give yaml file as argument." << std::endl; 00048 exit(-1); 00049 } 00050 00051 bool publish_clock = true; 00052 00053 std::string filename = argv[1]; 00054 00055 std::cout << filename << std::endl; 00056 00057 std::ifstream fin(filename.c_str()); 00058 if (fin.fail()) { 00059 ROS_ERROR("Could not open %s.", filename.c_str()); 00060 exit(-1); 00061 } 00062 00063 // dirname can modify what you pass it 00064 char* filename_copy = strdup(filename.c_str()); 00065 string bag_dir = string(dirname(filename_copy)); 00066 free(filename_copy); 00067 00068 cout << bag_dir << endl; 00069 00070 // Default values 00071 std::string bag_in_name = ""; 00072 00073 // load file names from yaml file 00074 YAML::Parser parser(fin); 00075 YAML::Node doc; 00076 parser.GetNextDocument(doc); 00077 try { 00078 doc["bag"] >> bag_in_name; 00079 } catch (YAML::InvalidScalar) { 00080 ROS_ERROR("The input file does not contain a bag tag or is invalid."); 00081 exit(-1); 00082 } 00083 00084 // Check input 00085 if (bag_in_name == "") { 00086 ROS_ERROR("No input bag file defined!"); 00087 return -1; 00088 } 00089 00090 if (bag_in_name[0] != '/') { 00091 bag_in_name = bag_dir + "/" + bag_in_name; 00092 } 00093 00094 const YAML::Node* n_videos = doc.FindValue("videos"); 00095 if (!n_videos) { 00096 ROS_ERROR("The input file does not contain a video tag or is invalid."); 00097 exit(-1); 00098 } 00099 00100 std::map<std::string, cv::VideoCapture*> topic_to_video_capture; 00101 00102 for (YAML::Iterator it_n_video = n_videos->begin(); it_n_video != n_videos->end(); ++it_n_video) { 00103 std::string video_filename; 00104 std::string video_topic; 00105 00106 try { 00107 (*it_n_video)["file"] >> video_filename; 00108 (*it_n_video)["topic"] >> video_topic; 00109 } catch (YAML::InvalidScalar) { 00110 ROS_ERROR("Invalid video specification: should contain 'file' and 'topic'."); 00111 exit(-1); 00112 } 00113 00114 if (video_filename[0] != '/') { 00115 video_filename = bag_dir + "/" + video_filename; 00116 } 00117 00118 cv::VideoCapture* video_capture = new cv::VideoCapture(video_filename); 00119 00120 if (!video_capture->isOpened()) { 00121 ROS_ERROR("Unable to open video: %s", video_filename.c_str()); 00122 return 0; 00123 } else ROS_INFO("Opened video %s for topic %s", video_filename.c_str(), video_topic.c_str()); 00124 00125 topic_to_video_capture[video_topic] = video_capture; 00126 } 00127 00128 // Load input bag file 00129 rosbag::Bag bag_in; 00130 bag_in.open(bag_in_name, rosbag::bagmode::Read); 00131 ROS_INFO("Opened %s", bag_in_name.c_str()); 00132 00133 // Get topics and time from input bag file 00134 rosbag::View view(bag_in); 00135 00136 cv::Mat rgb_frame; 00137 cv_bridge::CvImagePtr rgb_img_ptr(new cv_bridge::CvImage); 00138 sensor_msgs::ImagePtr rgb_img; 00139 00140 cv::Mat depth_frame; 00141 cv_bridge::CvImagePtr depth_img_ptr(new cv_bridge::CvImage); 00142 sensor_msgs::ImagePtr depth_img; 00143 00144 // Initialize node 00145 ros::init(argc, argv, "rosbag_video_play"); 00146 ros::NodeHandle nh; 00147 00148 std::map<std::string, ros::Publisher> topic_to_publisher; 00149 00150 ros::Publisher pub_clock; 00151 if (publish_clock) { 00152 pub_clock = nh.advertise<rosgraph_msgs::Clock>("/clock", 10, false); 00153 } 00154 00155 bool time_diff_initialized = false; 00156 ros::Duration time_diff_bag_real; 00157 00158 // Loop over messages and write topics to output bag file 00159 BOOST_FOREACH(rosbag::MessageInstance const m, view) { 00160 00161 if (!time_diff_initialized) { 00162 time_diff_bag_real = ros::Time(ros::WallTime::now().toSec()) - m.getTime(); 00163 time_diff_initialized = true; 00164 } 00165 00166 if (m.getTopic().find("/_trigger") != std::string::npos) { 00167 00168 std_msgs::BoolConstPtr img_rgb_trigger = m.instantiate<std_msgs::Bool>(); 00169 std_msgs::Float64ConstPtr img_depth_trigger = m.instantiate<std_msgs::Float64>(); 00170 00171 std::string image_topic = m.getTopic(); 00172 image_topic.replace(image_topic.end() - 9, image_topic.end(), ""); 00173 00174 std::map<std::string, cv::VideoCapture*>::iterator it_vc = topic_to_video_capture.find(image_topic); 00175 if (it_vc == topic_to_video_capture.end()) { 00176 ROS_ERROR("Image topic %s was not specified in YAML file.", image_topic.c_str()); 00177 exit(-1); 00178 } 00179 cv::VideoCapture* video_capture = it_vc->second; 00180 00181 if (img_rgb_trigger) { 00182 (*video_capture) >> rgb_frame; 00183 00184 if( rgb_frame.empty()) { 00185 ROS_ERROR("Unexpected end of video!"); 00186 } 00187 00188 // Add image, frame and encoding to the image message 00189 rgb_img_ptr->image = rgb_frame; 00190 rgb_img = rgb_img_ptr->toImageMsg(); 00191 rgb_img->header.frame_id = "/openni_rgb_optical_frame"; 00192 rgb_img->header.stamp = m.getTime(); 00193 rgb_img->encoding = "bgr8"; 00194 00195 std::map<std::string, ros::Publisher>::iterator it_publisher = topic_to_publisher.find(image_topic); 00196 ros::Publisher pub; 00197 00198 if (it_publisher == topic_to_publisher.end()) { 00199 pub = nh.advertise<sensor_msgs::Image>(image_topic, 10, false); 00200 topic_to_publisher[image_topic] = pub; 00201 } else { 00202 pub = it_publisher->second; 00203 } 00204 ros::WallTime::sleepUntil(ros::WallTime((m.getTime() + time_diff_bag_real).toSec())); 00205 pub.publish(rgb_img); 00206 00207 } else if (img_depth_trigger) { 00208 (*video_capture) >> depth_frame; 00209 00210 if(depth_frame.empty()) { 00211 ROS_ERROR("Unexpected end of depth video!"); 00212 } 00213 00214 cv::Mat depth_mat(depth_frame.rows, depth_frame.cols, CV_32FC1); 00215 00216 for(int y = 0; y < depth_frame.rows; y++) { 00217 for(int x = 0; x < depth_frame.cols; x++) { 00218 unsigned char dist_char = depth_frame.at<cv::Vec3b>(y, x)[0]; 00219 float distance = (float)dist_char / 255 * img_depth_trigger->data; 00220 depth_mat.at<float>(y, x) = distance; 00221 } 00222 } 00223 00224 // Add image, frame and encoding to the image message 00225 depth_img_ptr->image = depth_mat; 00226 depth_img = depth_img_ptr->toImageMsg(); 00227 depth_img->header.frame_id = "/openni_rgb_optical_frame"; 00228 depth_img->header.stamp = m.getTime(); 00229 depth_img->encoding = "32FC1"; 00230 00231 std::map<std::string, ros::Publisher>::iterator it_publisher = topic_to_publisher.find(image_topic); 00232 ros::Publisher pub; 00233 00234 if (it_publisher == topic_to_publisher.end()) { 00235 pub = nh.advertise<sensor_msgs::Image>(image_topic, 10, false); 00236 topic_to_publisher[image_topic] = pub; 00237 } else { 00238 pub = it_publisher->second; 00239 } 00240 00241 ros::WallTime::sleepUntil(ros::WallTime((m.getTime() + time_diff_bag_real).toSec())); 00242 pub.publish(depth_img); 00243 00244 } else { 00245 ROS_ERROR("Unknown trigger topic: %s", m.getTopic().c_str()); 00246 } 00247 } else { 00248 // any other message type 00249 00250 std::map<std::string, ros::Publisher>::iterator it_publisher = topic_to_publisher.find(m.getTopic()); 00251 ros::Publisher pub; 00252 if (it_publisher == topic_to_publisher.end()) { 00253 ros::AdvertiseOptions opts = ros::AdvertiseOptions(m.getTopic(), 10, m.getMD5Sum(), m.getDataType(), m.getMessageDefinition()); 00254 pub = nh.advertise(opts); 00255 topic_to_publisher[m.getTopic()] = pub; 00256 } else { 00257 pub = it_publisher->second; 00258 } 00259 00260 ros::WallTime::sleepUntil(ros::WallTime((m.getTime() + time_diff_bag_real).toSec())); 00261 pub.publish(m); 00262 } 00263 00264 if (publish_clock) { 00265 rosgraph_msgs::Clock clock_msg; 00266 clock_msg.clock = m.getTime(); 00267 pub_clock.publish(clock_msg); 00268 } 00269 00270 // Stop if user interrupted or if ROS core is no longer available 00271 if (!ros::ok()) { 00272 break; 00273 } 00274 00275 } 00276 00277 for (std::map<std::string, cv::VideoCapture*>::iterator it_vc = topic_to_video_capture.begin(); it_vc != topic_to_video_capture.end(); ++it_vc) { 00278 delete it_vc->second; 00279 } 00280 00281 bag_in.close(); 00282 ROS_INFO("Finished playing"); 00283 00284 return 0; 00285 00286 }