42#include <moveit_mesh_filter_export.h>
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);
88 void setRenderParameters(
GLRenderer& renderer)
const override;
94 void setFilterParameters(
GLRenderer& renderer)
const override;
104 void setCameraParameters(
float fx,
float fy,
float cx,
float cy);
110 void setBaseline(
float base_line);
116 void setDisparityResolution(
float disparity_resolution);
122 const Eigen::Vector3f& getPaddingCoefficients()
const override;
143 float disparity_resolution_;
149 const Eigen::Vector3f padding_coefficients_;
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,...
Abstract Interface defining Sensor Parameters.
Abstract Interface defining a sensor model for mesh filtering.
Parameters for Stereo-like devices.
~Parameters() override
Descturctor.
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