$search
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 * conversions between ROS and ViSP structures representing camera parameters 00038 * 00039 * Authors: 00040 * Filip Novotny 00041 * 00042 * 00043 *****************************************************************************/ 00044 00050 #include "camera.h" 00051 00052 namespace visp_bridge{ 00053 00054 vpCameraParameters toVispCameraParameters(const sensor_msgs::CameraInfo& cam_info){ 00055 return vpCameraParameters(cam_info.P[0 * 4 + 0],cam_info.P[1 * 4 + 1],cam_info.P[0 * 4 + 2],cam_info.P[1 * 4 + 2],-cam_info.D[0],cam_info.D[0]); 00056 } 00057 00058 sensor_msgs::CameraInfo toSensorMsgsCameraInfo(vpCameraParameters& cam_info, unsigned int cam_image_width, unsigned int cam_image_height ){ 00059 sensor_msgs::CameraInfo ret; 00060 00061 std::vector<double> D(5); 00062 D[0]=cam_info.get_kdu(); 00063 D[1] = D[2] = D[3] = D[4] = 0.; 00064 ret.D = D; 00065 ret.P.assign(0.); 00066 ret.K.assign(0.); 00067 ret.R.assign(0.); 00068 00069 ret.R[0] = 1.; 00070 ret.R[1 * 3 + 1] = 1.; 00071 ret.R[2 * 3 + 2] = 1.; 00072 00073 ret.P[0 * 4 + 0] = cam_info.get_px(); 00074 ret.P[1 * 4 + 1] = cam_info.get_py(); 00075 ret.P[0 * 4 + 2] = cam_info.get_u0(); 00076 ret.P[1 * 4 + 2] = cam_info.get_v0(); 00077 ret.P[2 * 4 + 2] = 1; 00078 00079 00080 ret.K[0 * 3 + 0] = cam_info.get_px(); 00081 ret.K[1 * 3 + 1] = cam_info.get_py(); 00082 ret.K[0 * 3 + 2] = cam_info.get_u0(); 00083 ret.K[1 * 3 + 2] = cam_info.get_v0(); 00084 ret.K[2 * 3 + 2] = 1; 00085 00086 ret.distortion_model = "plumb_bob"; 00087 ret.binning_x = 0; 00088 ret.binning_y = 0; 00089 ret.width = cam_image_width; 00090 ret.height = cam_image_height; 00091 00092 return ret; 00093 } 00094 } 00095