00001 /**************************************************************************** 00002 * 00003 * $Id: file.cpp 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 * 00038 * 00039 * Authors: 00040 * Filip Novotny 00041 * 00042 * 00043 *****************************************************************************/ 00044 00049 #include "ros/ros.h" 00050 #include "sensor_msgs/Image.h" 00051 #include "sensor_msgs/SetCameraInfo.h" 00052 #include "visp/vpImage.h" 00053 #include "visp/vpPoint.h" 00054 #include "visp/vpCameraParameters.h" 00055 #include <vector> 00056 #include <string> 00057 #include <boost/thread/thread.hpp> 00058 00059 00060 #ifndef __visp_camera_calibration_IMAGE_PROCESSING_H__ 00061 #define __visp_camera_calibration_IMAGE_PROCESSING_H__ 00062 namespace visp_camera_calibration 00063 { 00064 class ImageProcessing 00065 { 00066 ros::NodeHandle n_; 00067 ros::AsyncSpinner spinner_; 00068 00069 unsigned long queue_size_; 00070 bool pause_image_; 00071 00072 ros::Subscriber raw_image_subscriber_; 00073 ros::Publisher point_correspondence_publisher_; 00074 00075 ros::ServiceServer set_camera_info_bis_service_; 00076 ros::ServiceClient calibrate_service_; 00077 00078 vpImage<unsigned char> img_; 00079 00080 std::vector<vpPoint> selected_points_; 00081 std::vector<vpPoint> model_points_; 00082 00083 vpCameraParameters cam_; 00084 00085 bool is_initialized; 00086 00087 void init(); 00096 void rawImageCallback(const sensor_msgs::Image::ConstPtr& image); 00097 00102 bool setCameraInfoBisCallback(sensor_msgs::SetCameraInfo::Request &req, 00103 sensor_msgs::SetCameraInfo::Response &res); 00104 public: 00106 typedef boost::function<void (const sensor_msgs::Image::ConstPtr& )> 00107 raw_image_subscriber_callback_t; 00108 00110 typedef boost::function<bool (sensor_msgs::SetCameraInfo::Request&,sensor_msgs::SetCameraInfo::Response& res)> 00111 set_camera_info_bis_service_callback_t; 00112 00113 ImageProcessing(); 00114 void interface(); 00115 00116 virtual ~ImageProcessing(); 00117 }; 00118 } 00119 #endif /* IMAGE_PROCESSING_H_ */