usb_cam_reader_node.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2014, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 
28 #include <ros/ros.h>
29 #include <image_transport/image_transport.h>
30 #include <cv_bridge/cv_bridge.h>
31 #include <sensor_msgs/image_encodings.h>
32 #include <opencv2/imgproc/imgproc.hpp>
33 #include <opencv2/highgui/highgui.hpp>
34 
35 #include <camera_info_manager/camera_info_manager.h>
36 
37 
38 int main(int argc, char** argv)
39 {
40  ros::init(argc, argv, "usb_cam_reader");
41  ros::NodeHandle nh("~");
42  image_transport::ImageTransport it(nh);
43  image_transport::CameraPublisher img_pub = it.advertiseCamera("image_raw", 1);
44 
45 // Define the camera info url names
46  std::string camera_info_url;
47  std::string camera_name;
48 
49  nh.param("camera_name", camera_name, std::string("my_camera"));
50  nh.param("camera_info_url", camera_info_url, std::string(""));
51 
52  int cam_id;
53  nh.param<int>("cam_id",cam_id,0);
54  int img_width;
55  nh.param<int>("width",img_width,0);
56  int img_height;
57  nh.param<int>("height",img_height,0);
58 
59  camera_info_manager::CameraInfoManager cinfo_manager_(nh, camera_name, camera_info_url);
60 
61 // Creating the camara info manager
62 // camera_info_manager::CameraInfoManagerPtr cinfo_ = camera_info_manager::CameraInfoManagerPtr(new camera_info_manager::CameraInfoManager(nh, camera_name_, camera_info_url_));
63 
64 // Capture video stream
65  cv::VideoCapture captura(cam_id);
66 // Set the resolution to 720p, otherwise deafult is [640 480]
67 
68  if ( !captura.isOpened())
69  {
70  std::cout << "Impossible to open device" << std::endl;
71  return -1;
72  }
73  bool resolution = false;
74  sensor_msgs::CameraInfoPtr cam_info(new sensor_msgs::CameraInfo(cinfo_manager_.getCameraInfo()));
75 // std::cout << "width: " << cam_info->width << std::endl;
76 
77 // Checks if we are calibrating the camera for a given resolution
78  if ( img_width != 0 )
79  {
80  captura.set(CV_CAP_PROP_FRAME_WIDTH, img_width);
81  captura.set(CV_CAP_PROP_FRAME_HEIGHT, img_height);
82  }else{
83 // If not, checks if there is already a calibration resolution and gets it
84  if ( cam_info->width != 0)
85  {
86  captura.set(CV_CAP_PROP_FRAME_WIDTH, cam_info->width);
87  captura.set(CV_CAP_PROP_FRAME_HEIGHT, cam_info->height);
88  }
89  }
90 
91 
92 // Rate = 60 -> double the camera frame rate
93  ros::Rate loop_rate(60);
94  while (ros::ok())
95  {
96 
97  cv::Mat frame;
98  captura.read(frame);
99  if ( !resolution )
100  std::cout << frame.size() << std::endl;
101  resolution = true;
102 
103  if(img_pub.getNumSubscribers() > 0)
104  {
105  cv_bridge::CvImage my_image;
106 
107  my_image.header.stamp = ros::Time::now();
108  my_image.header.frame_id = "my_image";
109  my_image.encoding = "bgr8";
110  my_image.image = frame;
111 
112 
113  cam_info->header.frame_id = my_image.header.frame_id;
114  cam_info->header.stamp = my_image.header.stamp;
115 
116 // sensor_msgs::Image send_image;
117 // my_image.toImageMsg(send_image);
118  img_pub.publish( my_image.toImageMsg(), cam_info);
119 
120  }
121 
122 // sensor_msgs::ImagePtr msg = sensor_msgs::CvBridge::cvToImgMsg(image.Ipl(), "bgr8");
123 
124  ros::spinOnce();
125  loop_rate.sleep();
126  }
127 }
int main(int argc, char **argv)


usb_cam_reader
Author(s): Luís Pedras Carrão
autogenerated on Mon Mar 2 2015 01:32:56