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
00008
00009
00010 char filename[255];
00011 std::string path;
00012 cv::Mat image;
00013
00014 void IMcallback(const sensor_msgs::ImageConstPtr& image_msg, const sensor_msgs::CameraInfoConstPtr& info){
00015
00016 try
00017 {
00018 image = cv_bridge::toCvShare(image_msg, "bgr8")->image;
00019 } catch(cv_bridge::Exception)
00020 {
00021 ROS_ERROR("Unable to convert %s image to bgr8", image_msg->encoding.c_str());
00022 return;
00023 }
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 }
00036
00037 bool save_image(std_srvs::Empty::Request &dummyr, std_srvs::Empty::Response &dummyq){
00038
00039 if (!image.empty()) {
00040 time_t now = time(0);
00041 struct tm* tm = localtime(&now);
00042 sprintf(filename,"/home/quadbase/ros/quad_ros/quad_common/quad_save_image/images/%02d-%02d-%02d-%02d-%02d-%02d.jpeg",(tm->tm_year + 1900),(tm->tm_mon + 1),tm->tm_mday,tm->tm_hour, tm->tm_min, tm->tm_sec);
00043 cv::imwrite(filename, image);
00044 ROS_INFO("Image Saved");
00045 return true;
00046
00047 } else {
00048 ROS_WARN("Couldn't save image, no data!");
00049 return false;
00050 }
00051 }
00052
00053 int main(int argc, char** argv)
00054 {
00055 std::string img_topic;
00056 ros::init(argc, argv, "save_image", ros::init_options::AnonymousName);
00057 ros::NodeHandle nh;
00058 image_transport::ImageTransport it(nh);
00059
00060 nh.param<std::string>("topic", img_topic, "/usb_cam/image_raw/compressed");
00061 nh.param<std::string>("path", path, "/home/quadbase/ros/quad_ros/quad_common/quad_save_image/images/");
00062 ros::ServiceServer service = nh.advertiseService("save_image", save_image);
00063
00064 image_transport::CameraSubscriber sub = it.subscribeCamera(img_topic, 1, &IMcallback);
00065
00066 ros::spin();
00067 }