calibrator.h
Go to the documentation of this file.
00001 /****************************************************************************
00002  *
00003  * $Id: file.h 3496 2011-11-22 15:14:32Z fnovotny $
00004  *
00005  * This file is part of the ViSP software.
00006  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
00007  *
00008  * This software is free software; you can redistribute it and/or
00009  * modify it under the terms of the GNU General Public License
00010  * ("GPL") version 2 as published by the Free Software Foundation.
00011  * See the file LICENSE.txt at the root directory of this source
00012  * distribution for additional information about the GNU GPL.
00013  *
00014  * For using ViSP with software that can not be combined with the GNU
00015  * GPL, please contact INRIA about acquiring a ViSP Professional
00016  * Edition License.
00017  *
00018  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
00019  *
00020  * This software was developed at:
00021  * INRIA Rennes - Bretagne Atlantique
00022  * Campus Universitaire de Beaulieu
00023  * 35042 Rennes Cedex
00024  * France
00025  * http://www.irisa.fr/lagadic
00026  *
00027  * If you have questions regarding the use of this file, please contact
00028  * INRIA at visp@inria.fr
00029  *
00030  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
00031  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
00032  *
00033  * Contact visp@irisa.fr if any conditions of this licensing are
00034  * not clear to you.
00035  *
00036  * Description:
00037  * Calibrator node
00038  *
00039  * Authors:
00040  * Filip Novotny
00041  *
00042  *
00043  *****************************************************************************/
00044 
00050 #ifndef __visp_hand2eye_calibration_CALIBRATOR_H__
00051 #define __visp_hand2eye_calibration_CALIBRATOR_H__
00052 #include "ros/ros.h"
00053 
00054 #include "geometry_msgs/Transform.h"
00055 #include "visp_hand2eye_calibration/TransformArray.h"
00056 #include "visp_hand2eye_calibration/compute_effector_camera_quick.h"
00057 #include "visp_hand2eye_calibration/compute_effector_camera.h"
00058 #include "visp_hand2eye_calibration/reset.h"
00059 #include "image_proc/advertisement_checker.h"
00060 
00061 #include <vector>
00062 
00063 class vpHomogeneousMatrix;
00064 
00065 namespace visp_hand2eye_calibration{
00066  
00067   class Calibrator{
00068   private:    
00069     //subscribers. Must be class-persistant
00070     ros::ServiceServer compute_effector_camera_service_;
00071     ros::ServiceServer compute_effector_camera_quick_service_;
00072     ros::ServiceServer reset_service_;
00073     ros::Subscriber camera_object_subscriber_;
00074     ros::Subscriber world_effector_subscriber_;
00075     image_proc::AdvertisementChecker check_inputs_;
00076 
00077     std::vector<vpHomogeneousMatrix> cMo_vec_;
00078     std::vector<vpHomogeneousMatrix> wMe_vec_;
00079     ros::NodeHandle n_;
00080 
00081     unsigned int queue_size_;
00082 
00090     void cameraObjectCallback(const geometry_msgs::Transform::ConstPtr& trans);
00098     void worldEffectorCallback(const geometry_msgs::Transform::ConstPtr& trans);
00099 
00107     bool computeEffectorCameraCallback(visp_hand2eye_calibration::compute_effector_camera::Request  &req,
00108                                          visp_hand2eye_calibration::compute_effector_camera::Response &res );
00109 
00117     bool computeEffectorCameraQuickCallback(visp_hand2eye_calibration::compute_effector_camera_quick::Request  &req,
00118                                                visp_hand2eye_calibration::compute_effector_camera_quick::Response &res );
00122     bool resetCallback(visp_hand2eye_calibration::reset::Request  &req,
00123                         visp_hand2eye_calibration::reset::Response &res );
00124   public:
00126     typedef boost::function<bool (visp_hand2eye_calibration::compute_effector_camera::Request&,visp_hand2eye_calibration::compute_effector_camera::Response& res)>
00127       compute_effector_camera_service_callback_t;
00129     typedef boost::function<bool (visp_hand2eye_calibration::compute_effector_camera_quick::Request&,visp_hand2eye_calibration::compute_effector_camera_quick::Response& res)>
00130       compute_effector_camera_quick_service_callback_t;
00132     typedef boost::function<bool (visp_hand2eye_calibration::reset::Request&,visp_hand2eye_calibration::reset::Response& res)>
00133       reset_service_callback_t;
00134     
00136     typedef boost::function<void (const geometry_msgs::Transform::ConstPtr& )>
00137       camera_object_subscriber_callback_t;
00139     typedef boost::function<void (const geometry_msgs::Transform::ConstPtr& trans)>
00140       world_effector_subscriber_t;
00141 
00143     Calibrator();
00145     void spin();
00146     ~Calibrator();
00147   
00148   };
00149 }
00150 #endif


visp_hand2eye_calibration
Author(s): Filip Novotny
autogenerated on Mon Oct 6 2014 08:40:31