calibrator.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 
50 #include "ros/ros.h"
51 
52 #include "visp_camera_calibration/CalibPointArray.h"
53 #include <visp/vpPoint.h>
54 #include <visp/vpCalibration.h>
55 #include "visp_camera_calibration/calibrate.h"
56 #include <vector>
57 
58 #ifndef __visp_camera_calibration_CALIBRATOR_H__
59 #define __visp_camera_calibration_CALIBRATOR_H__
61 {
62  class Calibrator
63  {
64  private:
66 
67  unsigned long queue_size_;
68 
73 
74  std::vector<vpPoint> selected_points_;
75  std::vector<vpPoint> model_points_;
76  std::vector<vpCalibration> calibrations_;
83  void pointCorrespondenceCallback(const visp_camera_calibration::CalibPointArray::ConstPtr& point_correspondence);
88  bool calibrateCallback(visp_camera_calibration::calibrate::Request &req,
89  visp_camera_calibration::calibrate::Response &res);
90  public:
92  typedef boost::function<void (const visp_camera_calibration::CalibPointArray::ConstPtr& )>
94 
96  typedef boost::function<bool (visp_camera_calibration::calibrate::Request&,visp_camera_calibration::calibrate::Response& res)>
98  Calibrator();
99  void spin();
100  virtual ~Calibrator();
101  };
102 }
103 #endif /* CALIBRATOR_H_ */
visp_camera_calibration::Calibrator::pointCorrespondenceCallback
void pointCorrespondenceCallback(const visp_camera_calibration::CalibPointArray::ConstPtr &point_correspondence)
callback corresponding to the point_correspondence topic. Adds the obtained calibration pairs objects...
Definition: calibrator.cpp:81
visp_camera_calibration::Calibrator::~Calibrator
virtual ~Calibrator()
Definition: calibrator.cpp:155
ros.h
visp_camera_calibration::Calibrator::set_camera_info_service_
ros::ServiceClient set_camera_info_service_
Definition: calibrator.h:70
visp_camera_calibration::Calibrator
Definition: calibrator.h:62
visp_camera_calibration::Calibrator::Calibrator
Calibrator()
Definition: calibrator.cpp:62
visp_camera_calibration::Calibrator::calibrate_service_callback_t
boost::function< bool(visp_camera_calibration::calibrate::Request &, visp_camera_calibration::calibrate::Response &res)> calibrate_service_callback_t
service type declaration for calibrate service
Definition: calibrator.h:97
visp_camera_calibration::Calibrator::model_points_
std::vector< vpPoint > model_points_
Definition: calibrator.h:75
visp_camera_calibration::Calibrator::queue_size_
unsigned long queue_size_
Definition: calibrator.h:67
ros::ServiceServer
visp_camera_calibration::Calibrator::n_
ros::NodeHandle n_
Definition: calibrator.h:65
visp_camera_calibration::Calibrator::calibrate_service_
ros::ServiceServer calibrate_service_
Definition: calibrator.h:72
visp_camera_calibration::Calibrator::spin
void spin()
Definition: calibrator.cpp:151
ros::ServiceClient
visp_camera_calibration::Calibrator::point_correspondence_subscriber_callback_t
boost::function< void(const visp_camera_calibration::CalibPointArray::ConstPtr &)> point_correspondence_subscriber_callback_t
subscriber type declaration for raw_image topic subscriber
Definition: calibrator.h:93
visp_camera_calibration::Calibrator::point_correspondence_subscriber_
ros::Subscriber point_correspondence_subscriber_
Definition: calibrator.h:69
visp_camera_calibration::Calibrator::calibrateCallback
bool calibrateCallback(visp_camera_calibration::calibrate::Request &req, visp_camera_calibration::calibrate::Response &res)
service performing the calibration from all previously computed calibration objects.
Definition: calibrator.cpp:96
visp_camera_calibration::Calibrator::set_camera_info_bis_service_
ros::ServiceClient set_camera_info_bis_service_
Definition: calibrator.h:71
visp_camera_calibration::Calibrator::calibrations_
std::vector< vpCalibration > calibrations_
Definition: calibrator.h:76
visp_camera_calibration
Definition: calibrator.cpp:60
visp_camera_calibration::Calibrator::selected_points_
std::vector< vpPoint > selected_points_
Definition: calibrator.h:74
ros::NodeHandle
ros::Subscriber


visp_camera_calibration
Author(s): Filip Novotny
autogenerated on Sat Aug 24 2024 02:54:52