Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 #include <ros/ros.h>
00022 #include <image_transport/image_transport.h>
00023 #include <camera_info_manager/camera_info_manager.h>
00024 #include <opencv2/highgui/highgui.hpp>
00025 #include <opencv2/imgproc/imgproc.hpp>
00026 #include <cv_bridge/cv_bridge.h>
00027 #include <sstream>
00028 #include <boost/assign/list_of.hpp>
00029 
00030 
00031 
00032 sensor_msgs::CameraInfo get_default_camera_info_from_image(sensor_msgs::ImagePtr img){
00033     sensor_msgs::CameraInfo cam_info_msg;
00034     cam_info_msg.header.frame_id = img->header.frame_id;
00035     
00036     cam_info_msg.height = img->height;
00037     cam_info_msg.width = img->width;
00038     
00039     cam_info_msg.distortion_model = "plumb_bob";
00040     
00041     cam_info_msg.D.resize(5, 0.0);
00042     
00043     cam_info_msg.K = boost::assign::list_of(1.0) (0.0) (img->width/2.0)
00044                                            (0.0) (1.0) (img->height/2.0)
00045                                            (0.0) (0.0) (1.0);
00046     
00047     cam_info_msg.R = boost::assign::list_of (1.0) (0.0) (0.0)
00048                                             (0.0) (1.0) (0.0)
00049                                             (0.0) (0.0) (1.0);
00050     
00051     cam_info_msg.P = boost::assign::list_of (1.0) (0.0) (img->width/2.0) (0.0)
00052                                             (0.0) (1.0) (img->height/2.0) (0.0)
00053                                             (0.0) (0.0) (1.0) (0.0);
00054     return cam_info_msg;
00055 }
00056 
00057 
00058 
00059 int main(int argc, char** argv)
00060 {
00061     ros::init(argc, argv, "image_publisher");
00062     ros::NodeHandle nh;
00063     ros::NodeHandle _nh("~"); 
00064     image_transport::ImageTransport it(nh);
00065     image_transport::CameraPublisher pub = it.advertiseCamera("camera", 1);
00066 
00067     
00068     std::string video_stream_provider;
00069     cv::VideoCapture cap;
00070     if (_nh.getParam("video_stream_provider", video_stream_provider)){
00071         ROS_INFO_STREAM("Resource video_stream_provider: " << video_stream_provider);
00072         
00073         
00074         if (video_stream_provider.size() < 4){
00075             ROS_INFO_STREAM("Getting video from provider: /dev/video" << video_stream_provider);
00076             cap.open(atoi(video_stream_provider.c_str()));
00077         }
00078         else{
00079             ROS_INFO_STREAM("Getting video from provider: " << video_stream_provider);
00080             cap.open(video_stream_provider);
00081         }
00082     }
00083     else{
00084         ROS_ERROR("Failed to get param 'video_stream_provider'");
00085         return -1;
00086     }
00087 
00088     std::string camera_name;
00089     _nh.param("camera_name", camera_name, std::string("camera"));
00090     ROS_INFO_STREAM("Camera name: " << camera_name);
00091 
00092     int fps;
00093     _nh.param("fps", fps, 240);
00094     ROS_INFO_STREAM("Throttling to fps: " << fps);
00095 
00096     std::string frame_id;
00097     _nh.param("frame_id", frame_id, std::string("camera"));
00098     ROS_INFO_STREAM("Publishing with frame_id: " << frame_id);
00099 
00100     std::string camera_info_url;
00101     _nh.param("camera_info_url", camera_info_url, std::string(""));
00102     ROS_INFO_STREAM("Provided camera_info_url: '" << camera_info_url << "'");
00103 
00104     bool flip_horizontal;
00105     _nh.param("flip_horizontal", flip_horizontal, false);
00106     ROS_INFO_STREAM("Flip horizontal image is : " << ((flip_horizontal)?"true":"false"));
00107 
00108     bool flip_vertical;
00109     _nh.param("flip_vertical", flip_vertical, false);
00110     ROS_INFO_STREAM("Flip flip_vertical image is : " << ((flip_vertical)?"true":"false"));
00111 
00112     
00113     
00114     bool flip_image = true;
00115     int flip_value;
00116     if (flip_horizontal && flip_vertical)
00117         flip_value = 0; 
00118     else if (flip_horizontal)
00119         flip_value = 1;
00120     else if (flip_vertical)
00121         flip_value = -1;
00122     else
00123         flip_image = false;
00124 
00125     if(!cap.isOpened()){
00126         ROS_ERROR_STREAM("Could not open the stream.");
00127         return -1;
00128     }
00129 
00130     ROS_INFO_STREAM("Opened the stream, starting to publish.");
00131 
00132     cv::Mat frame;
00133     sensor_msgs::ImagePtr msg;
00134     sensor_msgs::CameraInfo cam_info_msg;
00135     std_msgs::Header header;
00136     header.frame_id = frame_id;
00137     camera_info_manager::CameraInfoManager cam_info_manager(nh, camera_name, camera_info_url);
00138     
00139     cam_info_msg = cam_info_manager.getCameraInfo();
00140 
00141     ros::Rate r(fps);
00142     while (nh.ok()) {
00143         cap >> frame;
00144         if (pub.getNumSubscribers() > 0){
00145             
00146             if(!frame.empty()) {
00147                 
00148                 if (flip_image)
00149                     cv::flip(frame, frame, flip_value);
00150                 msg = cv_bridge::CvImage(header, "bgr8", frame).toImageMsg();
00151                 
00152                 if (cam_info_msg.distortion_model == ""){
00153                     ROS_WARN_STREAM("No calibration file given, publishing a reasonable default camera info.");
00154                     cam_info_msg = get_default_camera_info_from_image(msg);
00155                     cam_info_manager.setCameraInfo(cam_info_msg);
00156                 }
00157                 
00158                 pub.publish(*msg, cam_info_msg, ros::Time::now());
00159             }
00160 
00161             ros::spinOnce();
00162         }
00163         r.sleep();
00164     }
00165 }