image_processing.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * $Id: file.cpp 3496 2011-11-22 15:14:32Z fnovotny $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  * Contact visp@irisa.fr if any conditions of this licensing are
34  * not clear to you.
35  *
36  * Description:
37  *
38  *
39  * Authors:
40  * Filip Novotny
41  *
42  *
43  *****************************************************************************/
44 
49 #include "ros/ros.h"
50 #include "sensor_msgs/Image.h"
51 #include "sensor_msgs/SetCameraInfo.h"
52 #include "visp/vpImage.h"
53 #include "visp/vpPoint.h"
54 #include "visp/vpCameraParameters.h"
55 #include <vector>
56 #include <string>
57 #include <boost/thread/thread.hpp>
58 
59 
60 #ifndef __visp_camera_calibration_IMAGE_PROCESSING_H__
61 #define __visp_camera_calibration_IMAGE_PROCESSING_H__
63 {
65 {
68 
69  unsigned long queue_size_;
71 
74 
77 
78  vpImage<unsigned char> img_;
79 
80  std::vector<vpPoint> selected_points_;
81  std::vector<vpPoint> model_points_;
82 
83  vpCameraParameters cam_;
84 
86 
87  void init();
96  void rawImageCallback(const sensor_msgs::Image::ConstPtr& image);
97 
102  bool setCameraInfoBisCallback(sensor_msgs::SetCameraInfo::Request &req,
103  sensor_msgs::SetCameraInfo::Response &res);
104 public:
106  typedef boost::function<void (const sensor_msgs::Image::ConstPtr& )>
108 
110  typedef boost::function<bool (sensor_msgs::SetCameraInfo::Request&,sensor_msgs::SetCameraInfo::Response& res)>
112 
113  ImageProcessing();
114  void interface();
115 
116  virtual ~ImageProcessing();
117 };
118 }
119 #endif /* IMAGE_PROCESSING_H_ */
boost::function< void(const sensor_msgs::Image::ConstPtr &)> raw_image_subscriber_callback_t
subscriber type declaration for raw_image topic subscriber
void rawImageCallback(const sensor_msgs::Image::ConstPtr &image)
callback corresponding to the raw_image topic. Computes a cMo from selected points on the image...
bool setCameraInfoBisCallback(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res)
service displaying.
boost::function< bool(sensor_msgs::SetCameraInfo::Request &, sensor_msgs::SetCameraInfo::Response &res)> set_camera_info_bis_service_callback_t
service type declaration for calibrate service


visp_camera_calibration
Author(s): Filip Novotny
autogenerated on Wed Jul 3 2019 19:48:03