Skip to content

Commit 539a94e

Browse files
committed
add comment in depth image projection shader for clarification
1 parent 23571b3 commit 539a94e

File tree

3 files changed

+6
-7
lines changed

3 files changed

+6
-7
lines changed

‎opengl_ros_lib/shader/fs_depth_image_projection.glsl‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ void main(void)
3737
accumulatedProbability = gridMapAccumulationWeight;
3838

3939
//store accumulated value in R channel
40-
//store 1.0 in G channel if the pixel is on the line
40+
//store 1.0 in G channel if valid depth is measured at the line
4141
//always store 1.0 in B channel
4242
fragmentColor = vec3(accumulatedProbability, validDepthMeasured, 1.0);
4343
}

‎opengl_ros_lib/shader/gs_depth_image_projection.glsl‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,8 @@ in vertex
1111
float depth;
1212
} input_vertices[1];
1313

14-
out float depth;
15-
out float hitDepth;
14+
out float depth; //depth value of the pixel on the line
15+
out float hitDepth; //depth value of the end of the line
1616

1717
void main(void)
1818
{

‎opengl_ros_lib/shader/vs_depth_image_projection.glsl‎

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,10 +45,9 @@ void main(void)
4545
);
4646
float depth = texelFetch(depthTexture, depthUV, 0).x * depthUnit; //convert to meter scale
4747

48+
//If valid depth is not measured at that pixel, treat as maximum depth is measured
4849
if (depth < validDepthInMeter.x || validDepthInMeter.y < depth)
49-
{
50-
depth = validDepthInMeter.y; //set to the max value
51-
}
50+
depth = validDepthInMeter.y;
5251

5352
//Now, convert image pixel (ix, iy, iz) to point in the optical frame (px, py, pz).
5453
//First, calculate px/pz and px/pz from ix/iz and iy/iz using projection matrix.
@@ -66,7 +65,7 @@ void main(void)
6665
//Projecting the point to the occupancy grid plane, in top down orthognal projection
6766
output_vertex.position = vec4(
6867
p.x / gridMapResolution / gridMapSize.x * 2, //convert to -1 to 1
69-
p.y / gridMapResolution / gridMapSize.y * 2, //set the origin on the bottom and flip upside down
68+
p.y / gridMapResolution / gridMapSize.y * 2, //set the origin at the center and flip upside down
7069
p.z / (gridMapLayerHeight / 2), //mapping -height/2 to height/2, to -1 to 1
7170
1.0
7271
);

0 commit comments

Comments
 (0)