sensor_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 <Eigen/Core> // for Vector3f
41 
42 namespace mesh_filter
43 {
44 // forward declarations
45 class GLRenderer;
46 
51 class SensorModel
52 {
53 public:
54  MOVEIT_CLASS_FORWARD(Parameters); // Defines ParametersPtr, ConstPtr, WeakPtr... etc
55 
60  class Parameters
61  {
62  public:
70  Parameters(unsigned width, unsigned height, float near_clipping_plane_distance, float far_clipping_plane_distance);
71 
73  virtual ~Parameters();
74 
82  virtual void setRenderParameters(GLRenderer& renderer) const = 0;
83 
88  virtual void setFilterParameters(GLRenderer& renderer) const = 0;
89 
94  virtual Parameters* clone() const = 0;
95 
100  virtual const Eigen::Vector3f& getPaddingCoefficients() const = 0;
101 
106  virtual void transformModelDepthToMetricDepth(float* depth) const;
107 
112  virtual void transformFilteredDepthToMetricDepth(float* depth) const;
113 
119  void setImageSize(unsigned width, unsigned height);
120 
126  void setDepthRange(float near, float far);
127 
132  unsigned getWidth() const;
133 
138  unsigned getHeight() const;
139 
144  float getNearClippingPlaneDistance() const;
145 
150  float getFarClippingPlaneDistance() const;
151 
152  protected:
154  unsigned width_;
155 
157  unsigned height_;
158 
161 
164  };
165 
169  virtual ~SensorModel();
170 };
171 } // namespace mesh_filter
mesh_filter::SensorModel::~SensorModel
virtual ~SensorModel()
virtual destructor
mesh_filter::SensorModel::Parameters::getWidth
unsigned getWidth() const
returns the width of depth maps
Definition: sensor_model.cpp:71
mesh_filter::GLRenderer
Abstracts the OpenGL frame buffer objects, and provides an interface to render meshes,...
Definition: gl_renderer.h:91
mesh_filter::SensorModel::Parameters::setImageSize
void setImageSize(unsigned width, unsigned height)
sets the image size
Definition: sensor_model.cpp:53
mesh_filter::SensorModel::Parameters::far_clipping_plane_distance_
float far_clipping_plane_distance_
distance of far clipping plane
Definition: sensor_model.h:192
mesh_filter::SensorModel::Parameters::getPaddingCoefficients
virtual const Eigen::Vector3f & getPaddingCoefficients() const =0
returns sensor dependent padding coefficients
mesh_filter::SensorModel::Parameters::setDepthRange
void setDepthRange(float near, float far)
sets the clipping range
Definition: sensor_model.cpp:59
mesh_filter::SensorModel::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(Parameters)
mesh_filter::SensorModel::Parameters::getNearClippingPlaneDistance
float getNearClippingPlaneDistance() const
returns distance to the near clipping plane
Definition: sensor_model.cpp:81
mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth
virtual void transformModelDepthToMetricDepth(float *depth) const
transforms depth values from rendered model to metric depth values
Definition: sensor_model.cpp:105
mesh_filter::SensorModel::Parameters::clone
virtual Parameters * clone() const =0
polymorphic clone method
mesh_filter::SensorModel::Parameters
Abstract Interface defining Sensor Parameters.
Definition: sensor_model.h:92
mesh_filter::SensorModel::Parameters::height_
unsigned height_
height of depth maps generated by the sensor
Definition: sensor_model.h:189
mesh_filter::SensorModel::Parameters::getHeight
unsigned getHeight() const
returns the height of depth maps
Definition: sensor_model.cpp:76
class_forward.h
mesh_filter::SensorModel::Parameters::getFarClippingPlaneDistance
float getFarClippingPlaneDistance() const
returns the distance to the far clipping plane
Definition: sensor_model.cpp:86
mesh_filter::SensorModel::Parameters::~Parameters
virtual ~Parameters()
virtual destructor
mesh_filter::SensorModel::Parameters::setFilterParameters
virtual void setFilterParameters(GLRenderer &renderer) const =0
sets the specific Filter Renderer parameters
mesh_filter::SensorModel::Parameters::transformFilteredDepthToMetricDepth
virtual void transformFilteredDepthToMetricDepth(float *depth) const
transforms depth values from filtered depth to metric depth values
Definition: sensor_model.cpp:177
mesh_filter::SensorModel::Parameters::near_clipping_plane_distance_
float near_clipping_plane_distance_
distance of near clipping plane
Definition: sensor_model.h:195
mesh_filter::SensorModel::Parameters::setRenderParameters
virtual void setRenderParameters(GLRenderer &renderer) const =0
method that sets required parameters for the renderer. Each sensor usually has its own shaders with s...
mesh_filter::SensorModel::Parameters::Parameters
Parameters(unsigned width, unsigned height, float near_clipping_plane_distance, float far_clipping_plane_distance)
Constructor taking core parameters that are required for all sensors.
Definition: sensor_model.cpp:42
mesh_filter::SensorModel::Parameters::width_
unsigned width_
width of depth maps generated by the sensor
Definition: sensor_model.h:186
mesh_filter
Definition: depth_self_filter_nodelet.h:47


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Fri Jun 21 2024 02:26:30