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 #pragma once
38 
40 #include <string>
41 
42 namespace mesh_filter
43 {
48 class StereoCameraModel : public SensorModel
49 {
50 public:
55  class Parameters : public SensorModel::Parameters
56  {
57  public:
71  Parameters(unsigned width, unsigned height, float near_clipping_plane_distance, float far_clipping_plane_distance,
72  float fx, float fy, float cx, float cy, float base_line, float disparity_resolution);
74  ~Parameters() override;
75 
80  SensorModel::Parameters* clone() const override;
81 
86  void setRenderParameters(GLRenderer& renderer) const override;
87 
92  void setFilterParameters(GLRenderer& renderer) const override;
93 
102  void setCameraParameters(float fx, float fy, float cx, float cy);
103 
108  void setBaseline(float base_line);
109 
114  void setDisparityResolution(float disparity_resolution);
115 
120  const Eigen::Vector3f& getPaddingCoefficients() const override;
121 
122  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
123 
124  private:
126  float fx_;
127 
129  float fy_;
130 
132  float cx_;
133 
135  float cy_;
136 
138  float base_line_;
139 
141  float disparity_resolution_;
142 
147  const Eigen::Vector3f padding_coefficients_;
148  };
149 
151  static const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming)
152 
154  static const std::string RENDER_VERTEX_SHADER_SOURCE;
155 
157  static const std::string RENDER_FRAGMENT_SHADER_SOURCE;
158 
160  static const std::string FILTER_VERTEX_SHADER_SOURCE;
161 
163  static const std::string FILTER_FRAGMENT_SHADER_SOURCE;
164 };
165 } // namespace mesh_filter
mesh_filter::StereoCameraModel::Parameters::setDisparityResolution
void setDisparityResolution(float disparity_resolution)
the quantization of disparity values in pixels. Usually 1/16th or 1/8th for OpenNI compatible devices
Definition: stereo_camera_model.cpp:76
mesh_filter::StereoCameraModel::FILTER_VERTEX_SHADER_SOURCE
static const std::string FILTER_VERTEX_SHADER_SOURCE
source code of the vertex shader used to filter the depth map
Definition: stereo_camera_model.h:224
mesh_filter::StereoCameraModel::FILTER_FRAGMENT_SHADER_SOURCE
static const std::string FILTER_FRAGMENT_SHADER_SOURCE
source code of the fragment shader used to filter the depth map
Definition: stereo_camera_model.h:227
sensor_model.h
mesh_filter::GLRenderer
Abstracts the OpenGL frame buffer objects, and provides an interface to render meshes,...
Definition: gl_renderer.h:91
mesh_filter::StereoCameraModel::Parameters::setRenderParameters
void setRenderParameters(GLRenderer &renderer) const override
set the shader parameters required for the model rendering
Definition: stereo_camera_model.cpp:81
mesh_filter::StereoCameraModel::Parameters::disparity_resolution_
float disparity_resolution_
resolution/quantization of disparity values
Definition: stereo_camera_model.h:237
mesh_filter::StereoCameraModel::Parameters::setFilterParameters
void setFilterParameters(GLRenderer &renderer) const override
set the shader parameters required for the mesh filtering
Definition: stereo_camera_model.cpp:99
mesh_filter::StereoCameraModel::RENDER_FRAGMENT_SHADER_SOURCE
static const std::string RENDER_FRAGMENT_SHADER_SOURCE
source code of the fragment shader used to render the meshes
Definition: stereo_camera_model.h:221
mesh_filter::StereoCameraModel::Parameters::cx_
float cx_
x component of principal point
Definition: stereo_camera_model.h:228
mesh_filter::StereoCameraModel::Parameters::fy_
float fy_
focal length in y-direction
Definition: stereo_camera_model.h:225
mesh_filter::SensorModel::Parameters
Abstract Interface defining Sensor Parameters.
Definition: sensor_model.h:92
mesh_filter::StereoCameraModel::Parameters::clone
SensorModel::Parameters * clone() const override
polymorphic clone method
Definition: stereo_camera_model.cpp:57
mesh_filter::StereoCameraModel::Parameters::padding_coefficients_
const Eigen::Vector3f padding_coefficients_
padding coefficients
Definition: stereo_camera_model.h:243
mesh_filter::StereoCameraModel::Parameters::setCameraParameters
void setCameraParameters(float fx, float fy, float cx, float cy)
sets the camera parameters of the pinhole camera where the disparities were obtained....
Definition: stereo_camera_model.cpp:63
mesh_filter::StereoCameraModel::RENDER_VERTEX_SHADER_SOURCE
static const std::string RENDER_VERTEX_SHADER_SOURCE
source code of the vertex shader used to render the meshes
Definition: stereo_camera_model.h:218
mesh_filter::StereoCameraModel::Parameters::getPaddingCoefficients
const Eigen::Vector3f & getPaddingCoefficients() const override
returns the coefficients that are required for obtaining the padding for meshes
Definition: stereo_camera_model.cpp:94
mesh_filter::StereoCameraModel::REGISTERED_PSDK_PARAMS
static const StereoCameraModel::Parameters & REGISTERED_PSDK_PARAMS
predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion)
Definition: stereo_camera_model.h:215
mesh_filter::StereoCameraModel::Parameters::setBaseline
void setBaseline(float base_line)
sets the base line = distance of the two projective devices (camera, projector-camera)
Definition: stereo_camera_model.cpp:71
mesh_filter::StereoCameraModel::Parameters::~Parameters
~Parameters() override
Descturctor.
mesh_filter::StereoCameraModel::Parameters::cy_
float cy_
y component of principal point
Definition: stereo_camera_model.h:231
mesh_filter::StereoCameraModel::Parameters::base_line_
float base_line_
distance of the two projective devices that are used to determine the disparities
Definition: stereo_camera_model.h:234
mesh_filter::StereoCameraModel::Parameters::fx_
float fx_
focal length in x-direction
Definition: stereo_camera_model.h:222
mesh_filter
Definition: depth_self_filter_nodelet.h:47
mesh_filter::StereoCameraModel::Parameters::Parameters
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.
Definition: stereo_camera_model.cpp:40
mesh_filter::StereoCameraModel::Parameters
Parameters for Stereo-like devices.
Definition: stereo_camera_model.h:119


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Mon May 27 2024 02:27:57