14 "attribute vec3 position;\n" 15 "attribute vec2 textureCoords;\n" 18 "out vec2 sampledUvs;\n" 22 "uniform mat4 transformationMatrix;\n" 23 "uniform mat4 projectionMatrix;\n" 24 "uniform mat4 cameraMatrix;\n" 26 "uniform sampler2D uvsSampler;\n" 27 "uniform sampler2D positionsSampler;\n" 29 "uniform float imageWidth;\n" 30 "uniform float imageHeight;\n" 31 "uniform float minDeltaZ;\n" 34 " float pixelWidth = 1.0 / imageWidth;\n" 35 " float pixelHeight = 1.0 / imageHeight;\n" 36 " vec2 tex = vec2(textureCoords.x, textureCoords.y);\n" 37 " vec4 pos = texture2D(positionsSampler, tex);\n" 38 " vec4 uvs = texture2D(uvsSampler, tex);\n" 40 " vec2 tex_left = vec2(max(textureCoords.x - pixelWidth, 0.0), textureCoords.y);\n" 41 " vec2 tex_right = vec2(min(textureCoords.x + pixelWidth, 1.0), textureCoords.y);\n" 42 " vec2 tex_top = vec2(textureCoords.x, max(textureCoords.y - pixelHeight, 0.0));\n" 43 " vec2 tex_buttom = vec2(textureCoords.x, min(textureCoords.y + pixelHeight, 1.0));\n" 45 " vec4 pos_left = texture2D(positionsSampler, tex_left);\n" 46 " vec4 pos_right = texture2D(positionsSampler, tex_right);\n" 47 " vec4 pos_top = texture2D(positionsSampler, tex_top);\n" 48 " vec4 pos_buttom = texture2D(positionsSampler, tex_buttom);\n" 50 " vec3 axis1 = vec3(normalize(mix(pos_right - pos, pos - pos_left, 0.5)));\n" 51 " vec3 axis2 = vec3(normalize(mix(pos_top - pos, pos - pos_buttom, 0.5)));\n" 52 " normal = cross(axis1, axis2);\n" 55 " if (uvs.x < 0.0) valid = 1.0;\n" 56 " if (uvs.y < 0.0) valid = 1.0;\n" 57 " if (uvs.x >= 1.0) valid = 1.0;\n" 58 " if (uvs.y >= 1.0) valid = 1.0;\n" 59 " if (abs(pos_left.z - pos.z) > minDeltaZ * pos.z) valid = 1.0;\n" 60 " if (abs(pos_right.z - pos.z) > minDeltaZ * pos.z) valid = 1.0;\n" 61 " if (abs(pos_top.z - pos.z) > minDeltaZ * pos.z) valid = 1.0;\n" 62 " if (abs(pos_buttom.z - pos.z) > minDeltaZ * pos.z) valid = 1.0;\n" 63 " if (abs(pos.z) < 0.01) valid = 1.0;\n" 64 " if (valid > 0.0) pos = vec4(1.0, 1.0, 1.0, 0.0);\n" 65 " else pos = vec4(pos.xyz, 1.0);\n" 66 " vec4 worldPosition = transformationMatrix * pos;\n" 67 " gl_Position = projectionMatrix * cameraMatrix * worldPosition;\n" 69 " sampledUvs = uvs.xy;\n" 78 "in vec2 sampledUvs;\n" 80 "out vec4 output_rgb;\n" 82 "uniform sampler2D textureSampler;\n" 83 "uniform float pickedID;\n" 84 "uniform float shaded;\n" 86 "const float Epsilon = 1e-10;\n" 88 "vec3 rgb2hsv(vec3 c)\n" 90 " vec4 K = vec4(0.0, -1.0 / 3.0, 2.0 / 3.0, -1.0);\n" 91 " vec4 p = mix(vec4(c.bg, K.wz), vec4(c.gb, K.xy), step(c.b, c.g));\n" 92 " vec4 q = mix(vec4(p.xyw, c.r), vec4(c.r, p.yzx), step(p.x, c.r));\n" 93 " float d = q.x - min(q.w, q.y);\n" 94 " float e = 1.0e-10;\n" 95 " return vec3(abs(q.z + (q.w - q.y) / (6.0 * d + e)), d / (q.x + e), q.x);\n" 97 "vec3 hsv2rgb(vec3 c)\n" 99 " vec4 K = vec4(1.0, 2.0 / 3.0, 1.0 / 3.0, 3.0);\n" 100 " vec3 p = abs(fract(c.xxx + K.xyz) * 6.0 - K.www);\n" 101 " return c.z * mix(K.xxx, clamp(p - K.xxx, 0.0, 1.0), c.y);\n" 103 "void main(void) {\n" 104 " if (valid > 0.0) discard;\n" 105 " vec4 color = texture2D(textureSampler, sampledUvs);\n" 106 " if (shaded > 0.0) {\n" 107 " vec3 light0 = vec3(0.0, 1.0, 0.0);" 108 " vec3 light1 = vec3(0.5, -1.0, 0.0);" 109 " vec3 light2 = vec3(-0.5, -1.0, 0.0);" 110 " vec3 light_dir0 = light0 - vec3(outPos);\n" 111 " vec3 light_dir1 = light1 - vec3(outPos);\n" 112 " vec3 light_dir2 = light2 - vec3(outPos);\n" 113 " float diffuse_factor0 = max(dot(normal,light_dir0), 0.0);\n" 114 " float diffuse_factor1 = max(dot(normal,light_dir1), 0.0);\n" 115 " float diffuse_factor2 = max(dot(normal,light_dir2), 0.0);\n" 116 " float diffuse_factor = 0.6 + diffuse_factor0 * 0.2 + diffuse_factor1 * 0.2 + diffuse_factor2 * 0.2;\n" 117 " color = clamp(diffuse_factor, 0.0, 1.0) * color;\n" 119 " output_rgb = vec4(color.xyz, 1.0);\n" 126 "attribute vec3 position;\n" 127 "attribute vec2 textureCoords;\n" 130 "out vec2 sampledUvs;\n" 133 "uniform mat4 transformationMatrix;\n" 134 "uniform mat4 projectionMatrix;\n" 135 "uniform mat4 cameraMatrix;\n" 137 "uniform sampler2D uvsSampler;\n" 138 "uniform sampler2D positionsSampler;\n" 140 "uniform float imageWidth;\n" 141 "uniform float imageHeight;\n" 142 "uniform float minDeltaZ;\n" 144 "void main(void) {\n" 145 " float pixelWidth = 1.0 / imageWidth;\n" 146 " float pixelHeight = 1.0 / imageHeight;\n" 147 " vec2 tex = vec2(textureCoords.x, textureCoords.y);\n" 148 " vec4 pos = texture2D(positionsSampler, tex);\n" 149 " vec4 uvs = texture2D(uvsSampler, tex);\n" 151 " vec2 tex_left = vec2(max(textureCoords.x - pixelWidth, 0.0), textureCoords.y);\n" 152 " vec2 tex_right = vec2(min(textureCoords.x + pixelWidth, 1.0), textureCoords.y);\n" 153 " vec2 tex_top = vec2(textureCoords.x, max(textureCoords.y - pixelHeight, 0.0));\n" 154 " vec2 tex_buttom = vec2(textureCoords.x, min(textureCoords.y + pixelHeight, 1.0));\n" 156 " vec4 pos_left = texture2D(positionsSampler, tex_left);\n" 157 " vec4 pos_right = texture2D(positionsSampler, tex_right);\n" 158 " vec4 pos_top = texture2D(positionsSampler, tex_top);\n" 159 " vec4 pos_buttom = texture2D(positionsSampler, tex_buttom);\n" 162 " if (uvs.x < 0.0) valid = 1.0;\n" 163 " if (uvs.y < 0.0) valid = 1.0;\n" 164 " if (uvs.x >= 1.0) valid = 1.0;\n" 165 " if (uvs.y >= 1.0) valid = 1.0;\n" 166 " if (abs(pos_left.z - pos.z) > minDeltaZ * pos.z) valid = 1.0;\n" 167 " if (abs(pos_right.z - pos.z) > minDeltaZ * pos.z) valid = 1.0;\n" 168 " if (abs(pos_top.z - pos.z) > minDeltaZ * pos.z) valid = 1.0;\n" 169 " if (abs(pos_buttom.z - pos.z) > minDeltaZ * pos.z) valid = 1.0;\n" 170 " if (abs(pos.z) < 0.01) valid = 1.0;\n" 171 " if (valid > 0.0) pos = vec4(1.0, 1.0, 1.0, 0.0);\n" 172 " else pos = vec4(pos.xyz, 1.0);\n" 173 " vec4 worldPosition = transformationMatrix * pos;\n" 174 " gl_Position = projectionMatrix * cameraMatrix * worldPosition;\n" 176 " sampledUvs = uvs.xy;\n" 185 "in vec2 sampledUvs;\n" 187 "out vec4 output_rgb;\n" 188 "out vec3 output_xyz;\n" 190 "uniform sampler2D textureSampler;\n" 191 "uniform float pickedID;\n" 192 "uniform float shaded;\n" 194 "void main(void) {\n" 195 " if (valid > 0.0) discard;\n" 196 " output_rgb = vec4(1.0);\n" 197 " output_xyz = outPos.xyz;\n" 202 #define NORMAL_WINDOW_SIZE 3 210 float zDelta = (zFar-
zNear);
211 float w = (right-
left);
214 m[0][0]=2.0f*zNear/
w;
216 m[0][2]=2.0f*(right+
left)/w;
220 m[1][1]=2.0f*zNear/
h;
226 m[2][2]=-(zFar+
zNear)/zDelta;
227 m[2][3]=-(2.f * zNear*
zFar)/zDelta;
253 const Fp32 magic = { (254U - 15U) << 23 };
254 const Fp32 was_infnan = { (127U + 16U) << 23 };
257 out.
u = (value & 0x7FFFU) << 13;
259 if (out.
f >= was_infnan.
f)
263 out.
u |= (value & 0x8000U) << 16;
268 pointcloud_shader::pointcloud_shader(std::unique_ptr<shader_program>
shader)
276 _shader = shader_program::load(
279 "position",
"textureCoords",
280 "output_rgb",
"output_xyz");
297 auto texture0_sampler_location =
_shader->get_uniform_location(
"textureSampler");
298 auto texture1_sampler_location =
_shader->get_uniform_location(
"positionsSampler");
299 auto texture2_sampler_location =
_shader->get_uniform_location(
"uvsSampler");
347 _origin_rgba_pbo.reset();
352 _pick_shader.reset();
354 _vertex_texture.reset();
355 _uvs_texture.reset();
362 perform_gl_action([&]()
364 cleanup_gpu_resources();
375 _vertex_texture = std::make_shared<rs2::texture_buffer>();
376 _uvs_texture = std::make_shared<rs2::texture_buffer>();
379 _model = vao::create(mesh);
381 _fbo = std::make_shared<fbo>(1, 1);
384 _viz = std::make_shared<rs2::texture_visualizer>();
390 _rgba_pbo.init(1, 1);
391 _origin_rgba_pbo.init(1, 1);
448 if (
now - front > std::chrono::seconds(1))
462 int width = vf_profile.width();
463 int height = vf_profile.height();
476 _model = vao::create(mesh);
489 if (
auto g = dynamic_cast<gpu_points_frame*>(points_f))
491 if (!
g->get_gpu_section().input_texture(0, &vertex_tex_id) ||
492 !
g->get_gpu_section().input_texture(1, &uv_tex_id)
506 auto render_pc = [
this, &vf_profile, curr_tex, vertex_tex_id, uv_tex_id]
514 shader->set_image_size(vf_profile.width(), vf_profile.height());
529 else _model->draw_points();
541 auto near_plane = gl_p(2,3)/(gl_p(2,2)-1);
542 auto far_plae = gl_p(2,3)/(gl_p(2,2)+1);
543 auto bottom = near_plane * (gl_p(1,2)-1)/gl_p(1,1);
544 auto top = near_plane * (gl_p(1,2)+1)/gl_p(1,1);
545 auto left = near_plane * (gl_p(0,2)-1)/gl_p(0,0);
546 auto right = near_plane * (gl_p(0,2)+1)/gl_p(0,0);
550 ox = (xy.
x / wh.x) * 2 - 1;
551 oy = (xy.
y / wh.y) * 2 - 1;
554 bottom / (0.5f * wh.y),
top / (0.5f * wh.y), near_plane, far_plae,
555 ox * (0.5f * wh.x), oy * (0.5f * wh.y));
560 _fbo->set_dims(fbo_width, fbo_height);
596 rgba8 rgba { 0, 0, 0, 0 };
604 auto center =
size / 2;
605 const auto half_window = NORMAL_WINDOW_SIZE / 2;
607 std::vector<half4> pos_halfs(
size);
615 _xyz_pbo.query(pos_halfs.data(), 0, 0,
621 std::vector<rs2::float3> pos_floats(
size);
624 auto pos = pos_halfs[
i];
628 pos_floats[
i] = {
x1,
y1, z1 };
633 auto left = pos_floats[center - half_window];
634 auto right = pos_floats[center + half_window];
635 auto pos = pos_floats[center];
638 auto down_up =
lerp(
pos - up, down -
pos, 0.5f) * (-1.f);
656 auto fbo_width = vp[2] /
scale;
657 auto fbo_height = vp[3] /
scale;
658 const auto viewport_x = vp[0] /
scale;
659 const auto viewport_y = vp[1] /
scale;
693 origin.
x = origin.
x - vp[0];
694 origin.
y = origin.
y - vp[1];
697 if (mouse_pick(origin,
rs2::float2{ float(vp[2]), float(vp[3]) },
727 for (
int x = 0;
x < width - 1; ++
x) {
728 for (
int y = 0;
y < height - 1; ++
y) {
729 auto a =
y * width +
x,
b =
y * width + x + 1,
c = (
y + 1)*width + x,
d = (
y + 1)*width + x + 1;
static const char * fragment_shader_text
float3 cross(const float3 &a, const float3 &b)
float lerp(float a, float b, float t)
#define GL_TEXTURE_MAG_FILTER
obj_mesh make_grid(int a, int b)
GLboolean GLboolean GLboolean b
static const auto OPTION_ORIGIN_PICKED
#define glFramebufferTexture2D
GLdouble GLdouble GLdouble top
option * _scale_factor_opt
static const auto OPTION_PICKED_Z
pointcloud_shader(const char *vertex_shader, const char *fragment_shader)
virtual void set(float value)=0
float2 * get_texture_coordinates()
GLenum GLenum GLenum GLenum GLenum scale
static const auto OPTION_PICKED_X
std::shared_ptr< pointcloud_shader > _shader
#define GL_TEXTURE_BINDING_2D
void perform_gl_action(T action)
uint32_t _camera_matrix_location
stream_profile get_profile() const
void set_shaded(bool shaded)
matrix4 frustum(float left, float right, float bottom, float top, float zNear, float zFar, float ox, float oy)
static const auto OPTION_FILLED
uint32_t _min_delta_z_location
static const auto OPTION_NORMAL_X
std::shared_ptr< rs2::texture_buffer > _vertex_texture
GLdouble GLdouble GLdouble w
void cleanup_gpu_resources() override
static const char * vertex_shader_text_picking
rs2::frame process_frame(const rs2::frame_source &source, const rs2::frame &f) override
GLfloat GLfloat GLfloat GLfloat h
static const auto OPTION_MOUSE_Y
GLdouble GLdouble GLdouble GLdouble GLdouble zFar
option & get_option(rs2_option id) override
uint32_t _projection_matrix_location
virtual float query() const =0
GLdouble GLdouble GLdouble GLdouble zNear
void register_option(rs2_option id, std::shared_ptr< option > option)
GLboolean GLboolean GLboolean GLboolean a
GLsizei const GLenum * attachments
#define GL_COLOR_BUFFER_BIT
#define glBindFramebuffer
std::shared_ptr< pointcloud_shader > _pick_shader
uint32_t _shaded_location
#define GL_COLOR_ATTACHMENT1
#define NORMAL_WINDOW_SIZE
#define GL_UNPACK_ALIGNMENT
std::shared_ptr< rs2::vao > _model
~pointcloud_renderer() override
int geometry_slot() const
GLint GLsizei GLsizei height
static const auto OPTION_NORMAL_Y
std::shared_ptr< rs2::fbo > _fbo
#define GL_TEXTURE_MIN_FILTER
void set_image_size(int width, int height)
std::shared_ptr< rs2::texture_buffer > _uvs_texture
static const auto OPTION_SHADED
void set_min_delta_z(float min_delta_z)
#define GL_DEPTH_BUFFER_BIT
option * _origin_picked_opt
uint32_t _height_location
GLuint GLfloat GLfloat GLfloat x1
uint32_t _transformation_matrix_location
static const struct @18 vertices[3]
#define GL_READ_FRAMEBUFFER
static const auto OPTION_SELECTED
static const auto OPTION_NORMAL_Z
static const auto OPTION_SCALE_FACTOR
uint32_t _picked_id_location
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
static const auto OPTION_PICKED_ID
void set_picked_id(float pid)
#define GL_COLOR_ATTACHMENT0
void create_gpu_resources() override
#define GL_PACK_ALIGNMENT
float2 translate_3d_to_2d(float3 point, matrix4 p, matrix4 v, matrix4 f, int32_t vp[4])
std::deque< std::chrono::high_resolution_clock::time_point > _durations
static const char * vertex_shader_text
const rs2::matrix4 & get_matrix(rs2_gl_matrix_type type) const
static const auto OPTION_MOUSE_X
static const auto OPTION_PICKED_Y
static const auto OPTION_MOUSE_PICK
void set_mvp(const rs2::matrix4 &model, const rs2::matrix4 &view, const rs2::matrix4 &projection)
static const char * fragment_shader_text_picking
bool glsl_enabled() const
float halfToNativeIeee(uint16_t value)
pbo< rgba8 > _origin_rgba_pbo
std::unique_ptr< rs2::shader_program > _shader