Skip to content

Commit

Permalink
Implement outlines for points 2d/3d/depth & use them for select & hov…
Browse files Browse the repository at this point in the history
…er in Viewer (#1568)

* support outline mask ids for point batches
* unify sphere_quad_coverage computation
* single point outlines, in style of line renderer
* outline based selection/hover for 2d points
* Removed a bunch of now unused functions
* implement outlines for depth clouds
* use match & unreachable!() when deciding on render pipelines for a given phase
  • Loading branch information
Wumpf committed Mar 13, 2023
1 parent 274032e commit 4b4f76a
Show file tree
Hide file tree
Showing 17 changed files with 498 additions and 326 deletions.
1 change: 1 addition & 0 deletions crates/re_renderer/examples/depth_cloud.rs
Original file line number Diff line number Diff line change
Expand Up @@ -179,6 +179,7 @@ impl RenderDepthClouds {
depth_dimensions: depth.dimensions,
depth_data: depth.data.clone(),
colormap: re_renderer::ColorMap::ColorMapTurbo,
outline_mask_id: Default::default(),
}],
)
.unwrap();
Expand Down
36 changes: 17 additions & 19 deletions crates/re_renderer/shader/depth_cloud.wgsl
Original file line number Diff line number Diff line change
Expand Up @@ -63,12 +63,12 @@ struct DepthCloudInfo {

/// The scale to apply to the radii of the backprojected points.
radius_scale: f32,
radius_scale_row_pad0: f32,
radius_scale_row_pad1: f32,
radius_scale_row_pad2: f32,

/// Configures color mapping mode, see `colormap.wgsl`.
colormap: u32,

/// Outline mask id for the outline mask pass.
outline_mask_id: UVec2,
};
@group(1) @binding(0)
var<uniform> depth_cloud_info: DepthCloudInfo;
Expand Down Expand Up @@ -106,23 +106,21 @@ fn vs_main(@builtin(vertex_index) vertex_idx: u32) -> VertexOut {

@fragment
fn fs_main(in: VertexOut) -> @location(0) Vec4 {
// There's easier ways to compute anti-aliasing for when we are in ortho mode since it's
// just circles.
// But it's very nice to have mostly the same code path and this gives us the sphere world
// position along the way.
let ray_in_world = camera_ray_to_world_pos(in.pos_in_world);

// Sphere intersection with anti-aliasing as described by Iq here
// https://www.shadertoy.com/view/MsSSWV
// (but rearranged and labeled to it's easier to understand!)
let d = ray_sphere_distance(ray_in_world, in.point_pos_in_world, in.point_radius);
let smallest_distance_to_sphere = d.x;
let closest_ray_dist = d.y;
let pixel_world_size = approx_pixel_world_size_at(closest_ray_dist);
if smallest_distance_to_sphere > pixel_world_size {
let coverage = sphere_quad_coverage(in.pos_in_world, in.point_radius, in.point_pos_in_world);
if coverage < 0.001 {
discard;
}
let coverage = 1.0 - saturate(smallest_distance_to_sphere / pixel_world_size);

return vec4(in.point_color.rgb, coverage);
}

@fragment
fn fs_main_outline_mask(in: VertexOut) -> @location(0) UVec2 {
// Output is an integer target, can't use coverage therefore.
// But we still want to discard fragments where coverage is low.
// Since the outline extends a bit, a very low cut off tends to look better.
let coverage = sphere_quad_coverage(in.pos_in_world, in.point_radius, in.point_pos_in_world);
if coverage < 1.0 {
discard;
}
return depth_cloud_info.outline_mask_id;
}
4 changes: 2 additions & 2 deletions crates/re_renderer/shader/lines.wgsl
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ fn vs_main(@builtin(vertex_index) vertex_idx: u32) -> VertexOut {
return out;
}

fn compute_coverage(in: VertexOut) -> f32{
fn compute_coverage(in: VertexOut) -> f32 {
var coverage = 1.0;
if has_any_flag(in.currently_active_flags, CAP_START_ROUND | CAP_END_ROUND) {
let distance_to_skeleton = length(in.position_world - in.closest_strip_position);
Expand All @@ -241,7 +241,7 @@ fn compute_coverage(in: VertexOut) -> f32{
@fragment
fn fs_main(in: VertexOut) -> @location(0) Vec4 {
var coverage = compute_coverage(in);
if coverage < 0.00001 {
if coverage < 0.001 {
discard;
}

Expand Down
30 changes: 16 additions & 14 deletions crates/re_renderer/shader/point_cloud.wgsl
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@ var color_texture: texture_2d<f32>;
struct BatchUniformBuffer {
world_from_obj: Mat4,
flags: u32,
_padding: UVec2, // UVec3 would take its own 4xf32 row, UVec2 is on the same as flags
outline_mask: UVec2,
};
@group(2) @binding(0)
var<uniform> batch: BatchUniformBuffer;
Expand Down Expand Up @@ -76,24 +78,12 @@ fn vs_main(@builtin(vertex_index) vertex_idx: u32) -> VertexOut {

@fragment
fn fs_main(in: VertexOut) -> @location(0) Vec4 {
// There's easier ways to compute anti-aliasing for when we are in ortho mode since it's just circles.
// But it's very nice to have mostly the same code path and this gives us the sphere world position along the way.
let ray = camera_ray_to_world_pos(in.world_position);

// Sphere intersection with anti-aliasing as described by Iq here
// https://www.shadertoy.com/view/MsSSWV
// (but rearranged and labeled to it's easier to understand!)
let d = ray_sphere_distance(ray, in.point_center, in.radius);
let smallest_distance_to_sphere = d.x;
let closest_ray_dist = d.y;
let pixel_world_size = approx_pixel_world_size_at(closest_ray_dist);
if smallest_distance_to_sphere > pixel_world_size {
let coverage = sphere_quad_coverage(in.world_position, in.radius, in.point_center);
if coverage < 0.001 {
discard;
}
let coverage = 1.0 - saturate(smallest_distance_to_sphere / pixel_world_size);

// TODO(andreas): Do we want manipulate the depth buffer depth to actually render spheres?

// TODO(andreas): Proper shading
// TODO(andreas): This doesn't even use the sphere's world position for shading, the world position used here is flat!
var shading = 1.0;
Expand All @@ -102,3 +92,15 @@ fn fs_main(in: VertexOut) -> @location(0) Vec4 {
}
return vec4(in.color.rgb * shading, coverage);
}

@fragment
fn fs_main_outline_mask(in: VertexOut) -> @location(0) UVec2 {
// Output is an integer target, can't use coverage therefore.
// But we still want to discard fragments where coverage is low.
// Since the outline extends a bit, a very low cut off tends to look better.
let coverage = sphere_quad_coverage(in.world_position, in.radius, in.point_center);
if coverage < 1.0 {
discard;
}
return batch.outline_mask;
}
16 changes: 16 additions & 0 deletions crates/re_renderer/shader/utils/sphere_quad.wgsl
Original file line number Diff line number Diff line change
Expand Up @@ -89,3 +89,19 @@ fn sphere_quad_span(vertex_idx: u32, point_pos: Vec3, point_unresolved_radius: f

return SphereQuadData(pos, radius);
}

fn sphere_quad_coverage(world_position: Vec3, radius: f32, point_center: Vec3) -> f32 {
// There's easier ways to compute anti-aliasing for when we are in ortho mode since it's just circles.
// But it's very nice to have mostly the same code path and this gives us the sphere world position along the way.
let ray = camera_ray_to_world_pos(world_position);

// Sphere intersection with anti-aliasing as described by Iq here
// https://www.shadertoy.com/view/MsSSWV
// (but rearranged and labeled to it's easier to understand!)
let d = ray_sphere_distance(ray, point_center, radius);
let smallest_distance_to_sphere = d.x;
let closest_ray_dist = d.y;
let pixel_world_size = approx_pixel_world_size_at(closest_ray_dist);

return 1.0 - saturate(smallest_distance_to_sphere / pixel_world_size);
}
74 changes: 69 additions & 5 deletions crates/re_renderer/src/point_cloud_builder.rs
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
use crate::{
allocator::CpuWriteGpuReadBuffer,
renderer::{
PointCloudBatchFlags, PointCloudBatchInfo, PointCloudDrawData, PointCloudDrawDataError,
PointCloudVertex,
OutlineMaskPreference, PointCloudBatchFlags, PointCloudBatchInfo, PointCloudDrawData,
PointCloudDrawDataError, PointCloudVertex,
},
Color32, DebugLabel, RenderContext, Size,
};
Expand Down Expand Up @@ -51,6 +51,8 @@ where
world_from_obj: glam::Mat4::IDENTITY,
flags: PointCloudBatchFlags::ENABLE_SHADING,
point_count: 0,
overall_outline_mask_ids: OutlineMaskPreference::NONE,
additional_outline_mask_ids_vertex_ranges: Vec::new(),
});

PointCloudBatchBuilder(self)
Expand Down Expand Up @@ -150,6 +152,13 @@ where
self
}

/// Sets an outline mask for every element in the batch.
#[inline]
pub fn outline_mask_ids(mut self, outline_mask_ids: OutlineMaskPreference) -> Self {
self.batch_mut().overall_outline_mask_ids = outline_mask_ids;
self
}

/// Each time we `add_points`, or upon builder drop, make sure that we
/// fill in any additional colors and user-data to have matched vectors.
fn extend_defaults(&mut self) {
Expand Down Expand Up @@ -215,6 +224,13 @@ where
max_points,
colors: &mut self.0.color_buffer,
user_data: &mut self.0.user_data,
additional_outline_mask_ids: &mut self
.0
.batches
.last_mut()
.unwrap()
.additional_outline_mask_ids_vertex_ranges,
start_vertex_index: old_size as _,
}
}

Expand All @@ -225,6 +241,7 @@ where
debug_assert_eq!(self.0.vertices.len(), self.0.color_buffer.num_written());
debug_assert_eq!(self.0.vertices.len(), self.0.user_data.len());

let vertex_index = self.0.vertices.len() as u32;
self.0.vertices.push(PointCloudVertex {
position,
radius: Size::AUTO,
Expand All @@ -236,6 +253,14 @@ where
vertex: self.0.vertices.last_mut().unwrap(),
color: &mut self.0.color_buffer,
user_data: self.0.user_data.last_mut().unwrap(),
vertex_index,
additional_outline_mask_ids: &mut self
.0
.batches
.last_mut()
.unwrap()
.additional_outline_mask_ids_vertex_ranges,
outline_mask_id: OutlineMaskPreference::NONE,
}
}

Expand Down Expand Up @@ -267,10 +292,14 @@ where
}
}

// TODO(andreas): Should remove single-point builder, practically this never makes sense as we're almost always dealing with arrays of points.
pub struct PointBuilder<'a, PerPointUserData> {
vertex: &'a mut PointCloudVertex,
color: &'a mut CpuWriteGpuReadBuffer<Color32>,
user_data: &'a mut PerPointUserData,
vertex_index: u32,
additional_outline_mask_ids: &'a mut Vec<(std::ops::Range<u32>, OutlineMaskPreference)>,
outline_mask_id: OutlineMaskPreference,
}

impl<'a, PerPointUserData> PointBuilder<'a, PerPointUserData>
Expand All @@ -294,17 +323,35 @@ where
*self.user_data = data;
self
}

/// Pushes additional outline mask ids for this point
///
/// Prefer the `overall_outline_mask_ids` setting to set the outline mask ids for the entire batch whenever possible!
pub fn outline_mask_id(mut self, outline_mask_id: OutlineMaskPreference) -> Self {
self.outline_mask_id = outline_mask_id;
self
}
}

impl<'a, PerPointUserData> Drop for PointBuilder<'a, PerPointUserData> {
fn drop(&mut self) {
if self.outline_mask_id.is_some() {
self.additional_outline_mask_ids.push((
self.vertex_index..self.vertex_index + 1,
self.outline_mask_id,
));
}
}
}

pub struct PointsBuilder<'a, PerPointUserData> {
// Vertices is a slice, which radii will update
vertices: &'a mut [PointCloudVertex],

// Colors and user-data are the Vec we append
// the data to if provided.
max_points: usize,
colors: &'a mut CpuWriteGpuReadBuffer<Color32>,
user_data: &'a mut Vec<PerPointUserData>,
additional_outline_mask_ids: &'a mut Vec<(std::ops::Range<u32>, OutlineMaskPreference)>,
start_vertex_index: u32,
}

impl<'a, PerPointUserData> PointsBuilder<'a, PerPointUserData>
Expand Down Expand Up @@ -354,4 +401,21 @@ where
.extend(data.take(self.max_points - self.user_data.len()));
self
}

/// Pushes additional outline mask ids for a specific range of points.
/// The range is relative to this builder's range, not the entire batch.
///
/// Prefer the `overall_outline_mask_ids` setting to set the outline mask ids for the entire batch whenever possible!
#[inline]
pub fn push_additional_outline_mask_ids_for_range(
self,
range: std::ops::Range<u32>,
ids: OutlineMaskPreference,
) -> Self {
self.additional_outline_mask_ids.push((
(range.start + self.start_vertex_index)..(range.end + self.start_vertex_index),
ids,
));
self
}
}

1 comment on commit 4b4f76a

@github-actions
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Rust Benchmark

Benchmark suite Current: 4b4f76a Previous: 4b2e51a Ratio
datastore/insert/batch/rects/insert 562959 ns/iter (± 1942) 549349 ns/iter (± 5216) 1.02
datastore/latest_at/batch/rects/query 1870 ns/iter (± 24) 1833 ns/iter (± 10) 1.02
datastore/latest_at/missing_components/primary 285 ns/iter (± 0) 275 ns/iter (± 4) 1.04
datastore/latest_at/missing_components/secondaries 430 ns/iter (± 2) 430 ns/iter (± 32) 1
datastore/range/batch/rects/query 150712 ns/iter (± 162) 148263 ns/iter (± 1165) 1.02
mono_points_arrow/generate_message_bundles 49943776 ns/iter (± 1019565) 44194262 ns/iter (± 1326471) 1.13
mono_points_arrow/generate_messages 136959101 ns/iter (± 1307296) 134860560 ns/iter (± 1624773) 1.02
mono_points_arrow/encode_log_msg 162981040 ns/iter (± 1575035) 159170609 ns/iter (± 1575552) 1.02
mono_points_arrow/encode_total 350729238 ns/iter (± 7978324) 346095093 ns/iter (± 2902861) 1.01
mono_points_arrow/decode_log_msg 187301200 ns/iter (± 1416312) 182029425 ns/iter (± 1915438) 1.03
mono_points_arrow/decode_message_bundles 74424512 ns/iter (± 1146664) 72303207 ns/iter (± 1267471) 1.03
mono_points_arrow/decode_total 256439555 ns/iter (± 2377718) 252226049 ns/iter (± 2493314) 1.02
batch_points_arrow/generate_message_bundles 331018 ns/iter (± 388) 325164 ns/iter (± 2887) 1.02
batch_points_arrow/generate_messages 6562 ns/iter (± 48) 6200 ns/iter (± 83) 1.06
batch_points_arrow/encode_log_msg 366666 ns/iter (± 1249) 360493 ns/iter (± 2536) 1.02
batch_points_arrow/encode_total 717026 ns/iter (± 2767) 710243 ns/iter (± 4535) 1.01
batch_points_arrow/decode_log_msg 346764 ns/iter (± 750) 346548 ns/iter (± 1808) 1.00
batch_points_arrow/decode_message_bundles 2139 ns/iter (± 2) 1996 ns/iter (± 32) 1.07
batch_points_arrow/decode_total 352874 ns/iter (± 616) 350147 ns/iter (± 1721) 1.01
arrow_mono_points/insert 7008291089 ns/iter (± 28976635) 7085119025 ns/iter (± 22729926) 0.99
arrow_mono_points/query 1777516 ns/iter (± 9268) 1723641 ns/iter (± 17748) 1.03
arrow_batch_points/insert 2650868 ns/iter (± 35917) 2561025 ns/iter (± 27607) 1.04
arrow_batch_points/query 16893 ns/iter (± 15) 16597 ns/iter (± 369) 1.02
arrow_batch_vecs/insert 42484 ns/iter (± 129) 41201 ns/iter (± 332) 1.03
arrow_batch_vecs/query 505625 ns/iter (± 577) 496623 ns/iter (± 3373) 1.02
tuid/Tuid::random 34 ns/iter (± 1) 34 ns/iter (± 0) 1

This comment was automatically generated by workflow using github-action-benchmark.

Please sign in to comment.