stereo_camera_model.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Suat Gedikli */
36 
37 #ifndef MOVEIT_MESH_FILTER_STEREO_CAMERA_MODEL_
38 #define MOVEIT_MESH_FILTER_STEREO_CAMERA_MODEL_
39 
41 #include <string>
42 
43 namespace mesh_filter
44 {
50 {
51 public:
57  {
58  public:
72  Parameters(unsigned width, unsigned height, float near_clipping_plane_distance, float far_clipping_plane_distance,
73  float fx, float fy, float cx, float cy, float base_line, float disparity_resolution);
75  ~Parameters();
76 
82 
87  void setRenderParameters(GLRenderer& renderer) const;
88 
93  void setFilterParameters(GLRenderer& renderer) const;
94 
103  void setCameraParameters(float fx, float fy, float cx, float cy);
104 
109  void setBaseline(float base_line);
110 
115  void setDisparityResolution(float disparity_resolution);
116 
121  const Eigen::Vector3f& getPaddingCoefficients() const;
122 
124 
125  private:
127  float fx_;
128 
130  float fy_;
131 
133  float cx_;
134 
136  float cy_;
137 
139  float base_line_;
140 
143 
148  const Eigen::Vector3f padding_coefficients_;
149  };
150 
153 
155  static const std::string renderVertexShaderSource;
156 
158  static const std::string renderFragmentShaderSource;
159 
161  static const std::string filterVertexShaderSource;
162 
164  static const std::string filterFragmentShaderSource;
165 };
166 } // namespace mesh_filter
167 #endif
Parameters(unsigned width, unsigned height, float near_clipping_plane_distance, float far_clipping_plane_distance, float fx, float fy, float cx, float cy, float base_line, float disparity_resolution)
Constructor.
const Eigen::Vector3f padding_coefficients_
padding coefficients
float cx_
x component of principal point
void setFilterParameters(GLRenderer &renderer) const
set the shader parameters required for the mesh filtering
float base_line_
distance of the two projective devices that are used to determine the disparities ...
Model for Disparity based devices. E.g stereo camera systems or OpenNI compatible devices...
float fy_
focal length in y-direction
static const std::string filterVertexShaderSource
source code of the vertex shader used to filter the depth map
void setDisparityResolution(float disparity_resolution)
the quantization of disparity values in pixels. Usually 1/16th or 1/8th for OpenNI compatible devices...
void setBaseline(float base_line)
sets the base line = distance of the two projective devices (camera, projector-camera) ...
Abstracts the OpenGL frame buffer objects, and provides an interface to render meshes, and retrieve the color and depth ap from opengl.
Definition: gl_renderer.h:58
float fx_
focal length in x-direction
static const StereoCameraModel::Parameters & RegisteredPSDKParams
predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion) ...
Parameters for Stereo-like devices.
float disparity_resolution_
resolution/quantization of disparity values
Abstract Interface defining Sensor Parameters.
Definition: sensor_model.h:61
static const std::string renderFragmentShaderSource
source code of the fragment shader used to render the meshes
static const std::string filterFragmentShaderSource
source code of the fragment shader used to filter the depth map
void setCameraParameters(float fx, float fy, float cx, float cy)
sets the camera parameters of the pinhole camera where the disparities were obtained. Usually the left camera
const Eigen::Vector3f & getPaddingCoefficients() const
returns the coefficients that are required for obtaining the padding for meshes
static const std::string renderVertexShaderSource
source code of the vertex shader used to render the meshes
void setRenderParameters(GLRenderer &renderer) const
set the shader parameters required for the model rendering
SensorModel::Parameters * clone() const
polymorphic clone method
float cy_
y component of principal point
Abstract Interface defining a sensor model for mesh filtering.
Definition: sensor_model.h:52


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sun Oct 18 2020 13:17:23