save_image_sync.cpp
Go to the documentation of this file.
00001 #include <opencv2/highgui/highgui.hpp>
00002 #include <ros/ros.h>
00003 #include <cv_bridge/cv_bridge.h>
00004 #include <image_transport/image_transport.h>
00005 #include <time.h>
00006 #include <std_srvs/Empty.h>
00007 #include <sensor_msgs/CompressedImage.h>
00008 #include <iostream>
00009 #include <iterator>
00010 #include <fstream>
00011 
00012 char filename[255];
00013 std::string path;
00014 sensor_msgs::CompressedImage img;
00015 cv::Mat image;
00016 using namespace std;
00017 
00018 
00019 void IMcallback(const sensor_msgs::CompressedImage& image_msg){
00020     img=image_msg;
00021 }
00022 
00023 bool save_image(std_srvs::Empty::Request &dummyr, std_srvs::Empty::Response &dummyq){
00024     if (!img.data.empty()) {
00025         time_t now = time(0);
00026         struct tm* tm = localtime(&now);
00027         sprintf(filename,"%s%02d-%02d-%02d-%02d-%02d-%02d.jpeg",path.c_str(),(tm->tm_year + 1900),(tm->tm_mon + 1),tm->tm_mday,tm->tm_hour, tm->tm_min, tm->tm_sec);
00028         ofstream FILE(filename, ios::out | ofstream::binary);
00029         std::copy(img.data.begin(), img.data.end(), ostreambuf_iterator<char>(FILE));
00030         FILE.close();
00031 
00032         ROS_INFO("Image Saved");
00033         return true;
00034 
00035     } else {
00036         ROS_WARN("Couldn't save image, no data!");
00037         return false;
00038     }
00039 }
00040 
00041 void TIMERcallback(const ros::TimerEvent& event){
00042     if (!img.data.empty()) {
00043         time_t now = time(0);
00044         struct tm* tm = localtime(&now);
00045         struct timeval tv;
00046         gettimeofday(&tv, NULL);
00047         sprintf(filename,"%s%02d-%02d-%02d-%02d-%02d-%02d-%ld.jpeg",path.c_str(),(tm->tm_year + 1900),(tm->tm_mon + 1),tm->tm_mday,tm->tm_hour, tm->tm_min, tm->tm_sec, tv.tv_usec);
00048         ofstream FILE(filename, ios::out | ofstream::binary);
00049         std::copy(img.data.begin(), img.data.end(), ostreambuf_iterator<char>(FILE));
00050         FILE.close();
00051 
00052         ROS_INFO("Image Saved");
00053     } else {
00054         ROS_WARN("Couldn't save image, no data!");
00055     }
00056 }
00057 
00058 int main(int argc, char** argv){
00059     std::string img_topic;
00060     ros::init(argc, argv, "save_image", ros::init_options::AnonymousName);
00061     ros::NodeHandle nh;
00062 
00063     nh.param<std::string>("topic", img_topic, "/usb_cam/image_raw/compressed");
00064     nh.param<std::string>("path", path, "/home/quadbase/ros/quad_ros/quad_common/quad_save_image/images/");
00065     ros::ServiceServer service = nh.advertiseService("save_image", save_image);
00066     ros::Subscriber sub = nh.subscribe(img_topic, 10, IMcallback);
00067     ros::Timer timer = nh.createTimer(ros::Duration(0.5), TIMERcallback);
00068 
00069     ros::spin();
00070 }


quad_save_image
Author(s): quad
autogenerated on Mon Jan 6 2014 11:48:15