calibrator.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * $Id: file.h 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  * Calibrator node
38  *
39  * Authors:
40  * Filip Novotny
41  *
42  *
43  *****************************************************************************/
44 
50 #ifndef __visp_hand2eye_calibration_CALIBRATOR_H__
51 #define __visp_hand2eye_calibration_CALIBRATOR_H__
52 #include "ros/ros.h"
53 
54 #include "geometry_msgs/Transform.h"
55 #include "visp_hand2eye_calibration/TransformArray.h"
56 #include "visp_hand2eye_calibration/compute_effector_camera_quick.h"
57 #include "visp_hand2eye_calibration/compute_effector_camera.h"
58 #include "visp_hand2eye_calibration/reset.h"
60 
61 #include <vector>
62 
63 class vpHomogeneousMatrix;
64 
66 
67  class Calibrator{
68  private:
69  //subscribers. Must be class-persistant
76 
77  std::vector<vpHomogeneousMatrix> cMo_vec_;
78  std::vector<vpHomogeneousMatrix> wMe_vec_;
80 
81  unsigned int queue_size_;
82 
90  void cameraObjectCallback(const geometry_msgs::Transform::ConstPtr& trans);
98  void worldEffectorCallback(const geometry_msgs::Transform::ConstPtr& trans);
99 
107  bool computeEffectorCameraCallback(visp_hand2eye_calibration::compute_effector_camera::Request &req,
108  visp_hand2eye_calibration::compute_effector_camera::Response &res );
109 
117  bool computeEffectorCameraQuickCallback(visp_hand2eye_calibration::compute_effector_camera_quick::Request &req,
118  visp_hand2eye_calibration::compute_effector_camera_quick::Response &res );
122  bool resetCallback(visp_hand2eye_calibration::reset::Request &req,
123  visp_hand2eye_calibration::reset::Response &res );
124  public:
126  typedef boost::function<bool (visp_hand2eye_calibration::compute_effector_camera::Request&,visp_hand2eye_calibration::compute_effector_camera::Response& res)>
129  typedef boost::function<bool (visp_hand2eye_calibration::compute_effector_camera_quick::Request&,visp_hand2eye_calibration::compute_effector_camera_quick::Response& res)>
132  typedef boost::function<bool (visp_hand2eye_calibration::reset::Request&,visp_hand2eye_calibration::reset::Response& res)>
134 
136  typedef boost::function<void (const geometry_msgs::Transform::ConstPtr& )>
139  typedef boost::function<void (const geometry_msgs::Transform::ConstPtr& trans)>
141 
143  Calibrator();
145  void spin();
146  ~Calibrator();
147 
148  };
149 }
150 #endif
ros::Subscriber camera_object_subscriber_
Definition: calibrator.h:73
ros::ServiceServer compute_effector_camera_service_
Definition: calibrator.h:70
std::vector< vpHomogeneousMatrix > cMo_vec_
Definition: calibrator.h:77
std::vector< vpHomogeneousMatrix > wMe_vec_
Definition: calibrator.h:78
void worldEffectorCallback(const geometry_msgs::Transform::ConstPtr &trans)
callback corresponding to the world->effector topic.
Definition: calibrator.cpp:67
boost::function< void(const geometry_msgs::Transform::ConstPtr &)> camera_object_subscriber_callback_t
subscriber type declaration for camera->object topic subscriber
Definition: calibrator.h:137
bool resetCallback(visp_hand2eye_calibration::reset::Request &req, visp_hand2eye_calibration::reset::Response &res)
service reseting the acumulated data
Definition: calibrator.cpp:130
ros::Subscriber world_effector_subscriber_
Definition: calibrator.h:74
Calibrator()
advertises services and subscribes to topics
Definition: calibrator.cpp:139
boost::function< bool(visp_hand2eye_calibration::compute_effector_camera::Request &, visp_hand2eye_calibration::compute_effector_camera::Response &res)> compute_effector_camera_service_callback_t
service type declaration for effector->camera computation service
Definition: calibrator.h:127
image_proc::AdvertisementChecker check_inputs_
Definition: calibrator.h:75
boost::function< bool(visp_hand2eye_calibration::compute_effector_camera_quick::Request &, visp_hand2eye_calibration::compute_effector_camera_quick::Response &res)> compute_effector_camera_quick_service_callback_t
service type declaration for quick effector->camera computation service
Definition: calibrator.h:130
void cameraObjectCallback(const geometry_msgs::Transform::ConstPtr &trans)
callback corresponding to the camera->object topic.
Definition: calibrator.cpp:59
bool computeEffectorCameraCallback(visp_hand2eye_calibration::compute_effector_camera::Request &req, visp_hand2eye_calibration::compute_effector_camera::Response &res)
service computing world->effector transformation from accumulated data.
Definition: calibrator.cpp:75
boost::function< void(const geometry_msgs::Transform::ConstPtr &trans)> world_effector_subscriber_t
subscriber type declaration for world->effector topic subscriber
Definition: calibrator.h:140
boost::function< bool(visp_hand2eye_calibration::reset::Request &, visp_hand2eye_calibration::reset::Response &res)> reset_service_callback_t
service type declaration for reset service
Definition: calibrator.h:133
bool computeEffectorCameraQuickCallback(visp_hand2eye_calibration::compute_effector_camera_quick::Request &req, visp_hand2eye_calibration::compute_effector_camera_quick::Response &res)
service computing world->effector transformation from parameter-passed data.
Definition: calibrator.cpp:99
ros::ServiceServer compute_effector_camera_quick_service_
Definition: calibrator.h:71
void spin()
spins the ros node
Definition: calibrator.cpp:180


visp_hand2eye_calibration
Author(s): Filip Novotny
autogenerated on Wed Jul 3 2019 19:48:05