moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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#include <moveit_mesh_filter_export.h>
43
44namespace mesh_filter
45{
50class MOVEIT_MESH_FILTER_EXPORT StereoCameraModel : public SensorModel
51{
52public:
58 {
59 public:
73 Parameters(unsigned width, unsigned height, float near_clipping_plane_distance, float far_clipping_plane_distance,
74 float fx, float fy, float cx, float cy, float base_line, float disparity_resolution);
76 ~Parameters() override;
77
82 SensorModel::Parameters* clone() const override;
83
88 void setRenderParameters(GLRenderer& renderer) const override;
89
94 void setFilterParameters(GLRenderer& renderer) const override;
95
104 void setCameraParameters(float fx, float fy, float cx, float cy);
105
110 void setBaseline(float base_line);
111
116 void setDisparityResolution(float disparity_resolution);
117
122 const Eigen::Vector3f& getPaddingCoefficients() const override;
123
125
126 private:
128 float fx_;
129
131 float fy_;
132
134 float cx_;
135
137 float cy_;
138
140 float base_line_;
141
143 float disparity_resolution_;
144
149 const Eigen::Vector3f padding_coefficients_;
150 };
151
153 static const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming)
154
156 static const std::string RENDER_VERTEX_SHADER_SOURCE;
157
159 static const std::string RENDER_FRAGMENT_SHADER_SOURCE;
160
162 static const std::string FILTER_VERTEX_SHADER_SOURCE;
163
165 static const std::string FILTER_FRAGMENT_SHADER_SOURCE;
166};
167} // namespace mesh_filter
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
Abstracts the OpenGL frame buffer objects, and provides an interface to render meshes,...
Definition gl_renderer.h:63
Abstract Interface defining Sensor Parameters.
Abstract Interface defining a sensor model for mesh filtering.
Parameters for Stereo-like devices.
Model for Disparity based devices. E.g stereo camera systems or OpenNI compatible devices.
static const std::string RENDER_VERTEX_SHADER_SOURCE
source code of the vertex shader used to render the meshes
static const std::string RENDER_FRAGMENT_SHADER_SOURCE
source code of the fragment shader used to render the meshes
static const StereoCameraModel::Parameters & REGISTERED_PSDK_PARAMS
predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion)
static const std::string FILTER_FRAGMENT_SHADER_SOURCE
source code of the fragment shader used to filter the depth map
static const std::string FILTER_VERTEX_SHADER_SOURCE
source code of the vertex shader used to filter the depth map