occlusion-filter.h
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2018 Intel Corporation. All Rights Reserved.
3 
4 #pragma once
5 #include "../include/librealsense2/hpp/rs_frame.hpp"
7 
8 #define ROTATION_BUFFER_SIZE 32 // minimum limit that could be divided by all resolutions
9 #define VERTICAL_SCAN_WINDOW_SIZE 16
10 #define DEPTH_OCCLUSION_THRESHOLD 0.5f //meters
11 
12 namespace librealsense
13 {
19  };
20 
24  };
25 
26  class pointcloud;
27 
29  {
30  public:
32 
33  bool active(void) const { return (occlusion_none != _occlusion_filter); }
34 
35  void process(float3* points, float2* uv_map, const std::vector<float2> & pix_coord, const rs2::depth_frame& depth) const;
36 
37  void set_mode(uint8_t filter_type) { _occlusion_filter = (occlusion_rect_type)filter_type; }
39 
42 
44  {
45  // in L500 X-axis translation in extrinsic matrix is close to 0 and Y-axis is > 0 because RGB and depth sensors are vertically aligned
46  float extrensic_low_threshold = 0.001f; //meters
47  float extrensic_high_threshold = 0.01f; //meters
48  return ((extr.translation[0] < extrensic_low_threshold) && (extr.translation[1] > extrensic_high_threshold) ? vertical : horizontal);
49  }
50 
52  {
53  // extriniscs identity matrix indicates the same sensor, skip occlusion later
54  return (extr == identity_matrix());
55  }
56  private:
57 
58  friend class pointcloud;
59 
60  void monotonic_heuristic_invalidation(float3* points, float2* uv_map, const std::vector<float2> & pix_coord, const rs2::depth_frame& depth) const;
61  void comprehensive_invalidation(float3* points, float2* uv_map, const std::vector<float2> & pix_coord) const;
62 
65  mutable std::vector<float> _texels_depth; // Temporal translation table of (mapped_x*mapped_y) holds the minimal depth value among all depth pixels mapped to that texel
68  float _depth_units;
69  };
70 }
bool is_same_sensor(const rs2_extrinsics &extr)
void set_texel_intrinsics(const rs2_intrinsics &in)
void monotonic_heuristic_invalidation(float3 *points, float2 *uv_map, const std::vector< float2 > &pix_coord, const rs2::depth_frame &depth) const
float translation[3]
Definition: rs_sensor.h:99
void set_mode(uint8_t filter_type)
GLint GLint GLsizei GLsizei GLsizei depth
void set_scanning(uint8_t scanning)
occlusion_rect_type _occlusion_filter
unsigned char uint8_t
Definition: stdint.h:78
optional_value< rs2_intrinsics > _depth_intrinsics
rs2_extrinsics identity_matrix()
Definition: src/types.h:611
void comprehensive_invalidation(float3 *points, float2 *uv_map, const std::vector< float2 > &pix_coord) const
occlusion_scanning_type find_scanning_direction(const rs2_extrinsics &extr)
occlusion_scanning_type _occlusion_scanning
std::vector< float > _texels_depth
void set_depth_intrinsics(const rs2_intrinsics &in)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
Definition: rs_sensor.h:96
GLuint in
Definition: glext.h:8859
rs2_extrinsics extr
Definition: test-pose.cpp:258
Video stream intrinsics.
Definition: rs_types.h:58
optional_value< rs2_intrinsics > _texels_intrinsics
void process(float3 *points, float2 *uv_map, const std::vector< float2 > &pix_coord, const rs2::depth_frame &depth) const


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:38