camera_parameters.h
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
33 #ifndef _CAMERA_PARAMETERS_H_
34 #define _CAMERA_PARAMETERS_H_
35 
36 
37 //####################################################################
40 #include <ros/ros.h>
41 
42 #include <opencv2/imgproc/imgproc.hpp>
43 #include <opencv2/highgui/highgui.hpp>
44 #include <opencv2/core/core.hpp>
45 #include <sensor_msgs/PointCloud2.h>
46 #include <pcl/ros/conversions.h>
47 #include <pcl/point_cloud.h>
48 #include <pcl/point_types.h>
49 #include <pcl_ros/point_cloud.h>
50 
51 #include <tf/tf.h>
52 
53 //Define the class
55 {
56  // ------------------------------------------------------------------------------
57  //PUBLIC SECTION OF THE CLASS
58  // ------------------------------------------------------------------------------
59  public:
60 
61  // Constructor.
63  {
64  intrinsic.create(3, 4, CV_64FC1); //allocate intrinsic Matrix
65  extrinsic.create(4, 4, CV_64FC1); //allocate extrinsic Matrix
66  extrinsic_inverse.create(4, 4, CV_64FC1); //allocate the inverted extrinsic Matrix
67  distortion.create(1, 5, CV_64FC1); //allocate the inverted extrinsic Matrix
68  };
69 
70 
72  {
73 
74  };
75 
76  int set_intrinsic(double fx, double fy, double cx, double cy);
77  int set_extrinsic(double p11, double p12, double p13, double p14,
78  double p21, double p22, double p23, double p24,
79  double p31, double p32, double p33, double p34);
80  int set_extrinsic(tf::StampedTransform* t);
81  int set_extrinsic(tf::Transform* t);
82 
83  int set_distortion(double k1, double k2, double p1, double p2, double k3)
84  {
85  cv::Mat *M = &distortion;
86  M->at<double>(0,0) = k1; M->at<double>(0,1) = k2; M->at<double>(0,2) = p1; M->at<double>(0,3) = p2; M->at<double>(0,4) = k3;
87  return 1;
88  }
89 
90  int set_distortion_spherical(double calibration_width, double calibration_height, double cx, double cy, double param, double image_scale=1)
91  {
95  spherical_distortion_params.scale=image_scale;
98  return 1;
99  }
100 
101  int set_width_height_num_channels(int w, int h, int nc)
102  {
103  width = w;
104  height = h;
105  num_channels = nc;
106  return 1;
107  }
108 
109  cv::Mat distortion; //the distortion matrix 1,5 cv_64F
110  cv::Mat intrinsic; //the intrinsic matrix 3,4 cv_64F
111  cv::Mat extrinsic; //the extrinsic matrix 4,4 cv_64F
112  cv::Mat extrinsic_inverse; //the extrinsic matrix 4,4 cv_64F
113  cv::Mat transformation; //the extrinsic matrix 4,4 cv_64F
114  std::vector<pcl::PointXY> pixels_canvas; //a list of points correcponding to the canvas
115  ros::Time stamp;
116  int width;
117  int height;
119  tf::StampedTransform camera_6dof_position;
120 
121  struct
122  {
125  double cx,cy,param;
126  double scale;
128 };
129 
130 #endif
131 
tf::StampedTransform camera_6dof_position
struct class_camera_parameters::@0 spherical_distortion_params
int set_extrinsic(double p11, double p12, double p13, double p14, double p21, double p22, double p23, double p24, double p31, double p32, double p33, double p34)
sets extrinsic parameters
int set_distortion_spherical(double calibration_width, double calibration_height, double cx, double cy, double param, double image_scale=1)
int set_distortion(double k1, double k2, double p1, double p2, double k3)
std::vector< pcl::PointXY > pixels_canvas
int set_intrinsic(double fx, double fy, double cx, double cy)
sets intrinsic parameters from a 3x3 CvMat
int set_width_height_num_channels(int w, int h, int nc)


polygon_primitives_extraction
Author(s): Miguel Oliveira
autogenerated on Mon Mar 2 2015 01:32:41