Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_MESH_FILTER_STEREO_CAMERA_MODEL_
00038 #define MOVEIT_MESH_FILTER_STEREO_CAMERA_MODEL_
00039
00040 #include <moveit/mesh_filter/sensor_model.h>
00041 #include <string>
00042
00043 namespace mesh_filter
00044 {
00049 class StereoCameraModel : public SensorModel
00050 {
00051 public:
00056 class Parameters : public SensorModel::Parameters
00057 {
00058 public:
00072 Parameters(unsigned width, unsigned height, float near_clipping_plane_distance, float far_clipping_plane_distance,
00073 float fx, float fy, float cx, float cy, float base_line, float disparity_resolution);
00075 ~Parameters();
00076
00081 SensorModel::Parameters* clone() const;
00082
00087 void setRenderParameters(GLRenderer& renderer) const;
00088
00093 void setFilterParameters(GLRenderer& renderer) const;
00094
00103 void setCameraParameters(float fx, float fy, float cx, float cy);
00104
00109 void setBaseline(float base_line);
00110
00115 void setDisparityResolution(float disparity_resolution);
00116
00121 const Eigen::Vector3f& getPaddingCoefficients() const;
00122
00123 private:
00125 float fx_;
00126
00128 float fy_;
00129
00131 float cx_;
00132
00134 float cy_;
00135
00137 float base_line_;
00138
00140 float disparity_resolution_;
00141
00146 const Eigen::Vector3f padding_coefficients_;
00147 };
00148
00150 static const StereoCameraModel::Parameters& RegisteredPSDKParams;
00151
00153 static const std::string renderVertexShaderSource;
00154
00156 static const std::string renderFragmentShaderSource;
00157
00159 static const std::string filterVertexShaderSource;
00160
00162 static const std::string filterFragmentShaderSource;
00163 };
00164 }
00165 #endif