Skip to content

Commit

Permalink
GPU tensor colormapping (#1841)
Browse files Browse the repository at this point in the history
* Refactor: introduce struct SliceSelection

* Refactor: use SliceSelection inside of ViewTensorState

* MVP of tensor colormapping on GPU

* Remove old ui code

* Support 64-bit tensors by narrowing to f32

* Allow more colormap options

* Clippy

* Report range errors instead of ignoring them

* Sort colormaps

* Shorten function name

* Create module gpu_bridge

* Move some code around

* Simnplify API

* Create ViewBuilder::new

* Fix missing colon in lint.py

* fix typos and formatting

* Disable texture filtering options for tensors for now

* Update docstrings

* Add profile scopes

* ViewBuilder cleanup

* Make ViewBuilder::setup non-Option

* Remove Result from thing that cannot fail

* Fix colormap numbering

* review cleanup

* pass in debug_name

* Unify the `range` function

* typo
  • Loading branch information
emilk authored Apr 14, 2023
1 parent e8e2d9b commit fe7ac0e
Show file tree
Hide file tree
Showing 26 changed files with 812 additions and 780 deletions.
13 changes: 7 additions & 6 deletions crates/re_data_store/src/entity_properties.rs
Original file line number Diff line number Diff line change
Expand Up @@ -143,23 +143,24 @@ impl ExtraQueryHistory {
pub enum Colormap {
/// Perceptually even
Grayscale,

Inferno,
Magma,
Plasma,
#[default]
Turbo,
Viridis,
Plasma,
Magma,
Inferno,
}

impl std::fmt::Display for Colormap {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
f.write_str(match self {
Colormap::Grayscale => "Grayscale",
Colormap::Inferno => "Inferno",
Colormap::Magma => "Magma",
Colormap::Plasma => "Plasma",
Colormap::Turbo => "Turbo",
Colormap::Viridis => "Viridis",
Colormap::Plasma => "Plasma",
Colormap::Magma => "Magma",
Colormap::Inferno => "Inferno",
})
}
}
Expand Down
19 changes: 19 additions & 0 deletions crates/re_log_types/src/data.rs
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,25 @@ impl TensorDataType {
}
}

#[inline]
pub fn min_value(&self) -> f64 {
match self {
Self::U8 => u8::MIN as _,
Self::U16 => u16::MIN as _,
Self::U32 => u32::MIN as _,
Self::U64 => u64::MIN as _,

Self::I8 => i8::MIN as _,
Self::I16 => i16::MIN as _,
Self::I32 => i32::MIN as _,
Self::I64 => i64::MIN as _,

Self::F16 => f16::MIN.into(),
Self::F32 => f32::MIN as _,
Self::F64 => f64::MIN,
}
}

#[inline]
pub fn max_value(&self) -> f64 {
match self {
Expand Down
72 changes: 33 additions & 39 deletions crates/re_renderer/examples/2d.rs
Original file line number Diff line number Diff line change
Expand Up @@ -225,25 +225,22 @@ impl framework::Example for Render2D {
vec![
// 2d view to the left
{
let mut view_builder = ViewBuilder::default();
view_builder
.setup_view(
re_ctx,
TargetConfiguration {
name: "2D".into(),
resolution_in_pixel: splits[0].resolution_in_pixel,
view_from_world: macaw::IsoTransform::IDENTITY,
projection_from_view: Projection::Orthographic {
camera_mode:
view_builder::OrthographicCameraMode::TopLeftCornerAndExtendZ,
vertical_world_size: splits[0].resolution_in_pixel[1] as f32,
far_plane_distance: 1000.0,
},
pixels_from_point,
..Default::default()
let mut view_builder = ViewBuilder::new(
re_ctx,
TargetConfiguration {
name: "2D".into(),
resolution_in_pixel: splits[0].resolution_in_pixel,
view_from_world: macaw::IsoTransform::IDENTITY,
projection_from_view: Projection::Orthographic {
camera_mode:
view_builder::OrthographicCameraMode::TopLeftCornerAndExtendZ,
vertical_world_size: splits[0].resolution_in_pixel[1] as f32,
far_plane_distance: 1000.0,
},
)
.unwrap();
pixels_from_point,
..Default::default()
},
);
view_builder.queue_draw(&line_strip_draw_data);
view_builder.queue_draw(&point_draw_data);
view_builder.queue_draw(&rectangle_draw_data);
Expand All @@ -258,7 +255,6 @@ impl framework::Example for Render2D {
},
// and 3d view of the same scene to the right
{
let mut view_builder = ViewBuilder::default();
let seconds_since_startup = time.seconds_since_startup();
let camera_rotation_center = screen_size.extend(0.0) * 0.5;
let camera_position = glam::vec3(
Expand All @@ -267,27 +263,25 @@ impl framework::Example for Render2D {
seconds_since_startup.cos(),
) * screen_size.x.max(screen_size.y)
+ camera_rotation_center;
view_builder
.setup_view(
re_ctx,
view_builder::TargetConfiguration {
name: "3D".into(),
resolution_in_pixel: splits[1].resolution_in_pixel,
view_from_world: macaw::IsoTransform::look_at_rh(
camera_position,
camera_rotation_center,
glam::Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
pixels_from_point,
..Default::default()
let mut view_builder = ViewBuilder::new(
re_ctx,
view_builder::TargetConfiguration {
name: "3D".into(),
resolution_in_pixel: splits[1].resolution_in_pixel,
view_from_world: macaw::IsoTransform::look_at_rh(
camera_position,
camera_rotation_center,
glam::Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
)
.unwrap();
pixels_from_point,
..Default::default()
},
);
let command_buffer = view_builder
.queue_draw(&line_strip_draw_data)
.queue_draw(&point_draw_data)
Expand Down
78 changes: 36 additions & 42 deletions crates/re_renderer/examples/depth_cloud.rs
Original file line number Diff line number Diff line change
Expand Up @@ -110,28 +110,25 @@ impl RenderDepthClouds {
builder.to_draw_data(re_ctx).unwrap()
};

let mut view_builder = ViewBuilder::default();
view_builder
.setup_view(
re_ctx,
view_builder::TargetConfiguration {
name: "Point Cloud".into(),
resolution_in_pixel,
view_from_world: IsoTransform::look_at_rh(
self.camera_position,
Vec3::ZERO,
Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
pixels_from_point,
..Default::default()
let mut view_builder = ViewBuilder::new(
re_ctx,
view_builder::TargetConfiguration {
name: "Point Cloud".into(),
resolution_in_pixel,
view_from_world: IsoTransform::look_at_rh(
self.camera_position,
Vec3::ZERO,
Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
)
.unwrap();
pixels_from_point,
..Default::default()
},
);

let command_buffer = view_builder
.queue_draw(&GenericSkyboxDrawData::new(re_ctx))
Expand Down Expand Up @@ -191,28 +188,25 @@ impl RenderDepthClouds {
)
.unwrap();

let mut view_builder = ViewBuilder::default();
view_builder
.setup_view(
re_ctx,
view_builder::TargetConfiguration {
name: "Depth Cloud".into(),
resolution_in_pixel,
view_from_world: IsoTransform::look_at_rh(
self.camera_position,
Vec3::ZERO,
Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
pixels_from_point,
..Default::default()
let mut view_builder = ViewBuilder::new(
re_ctx,
view_builder::TargetConfiguration {
name: "Depth Cloud".into(),
resolution_in_pixel,
view_from_world: IsoTransform::look_at_rh(
self.camera_position,
Vec3::ZERO,
Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
)
.unwrap();
pixels_from_point,
..Default::default()
},
);

let command_buffer = view_builder
.queue_draw(&GenericSkyboxDrawData::new(re_ctx))
Expand Down
13 changes: 5 additions & 8 deletions crates/re_renderer/examples/framework.rs
Original file line number Diff line number Diff line change
Expand Up @@ -288,14 +288,11 @@ impl<E: Example + 'static> Application<E> {
});

for draw_result in &draw_results {
draw_result
.view_builder
.composite(
&self.re_ctx,
&mut composite_pass,
draw_result.target_location,
)
.expect("Failed to composite view main surface");
draw_result.view_builder.composite(
&self.re_ctx,
&mut composite_pass,
draw_result.target_location,
);
}
};

Expand Down
3 changes: 1 addition & 2 deletions crates/re_renderer/examples/multiview.rs
Original file line number Diff line number Diff line change
Expand Up @@ -210,8 +210,7 @@ impl Multiview {
draw_data: &D,
index: u32,
) -> (ViewBuilder, wgpu::CommandBuffer) {
let mut view_builder = ViewBuilder::default();
view_builder.setup_view(re_ctx, target_cfg).unwrap();
let mut view_builder = ViewBuilder::new(re_ctx, target_cfg);

if self
.take_screenshot_next_frame_for_view
Expand Down
53 changes: 23 additions & 30 deletions crates/re_renderer/examples/outlines.rs
Original file line number Diff line number Diff line change
Expand Up @@ -40,44 +40,37 @@ impl framework::Example for Outlines {
time: &framework::Time,
pixels_from_point: f32,
) -> Vec<framework::ViewDrawResult> {
let mut view_builder = ViewBuilder::default();

if !self.is_paused {
self.seconds_since_startup += time.last_frame_duration.as_secs_f32();
}
let seconds_since_startup = self.seconds_since_startup;
// TODO(#1426): unify camera logic between examples.
let camera_position = glam::vec3(1.0, 3.5, 7.0);

view_builder
.setup_view(
re_ctx,
TargetConfiguration {
name: "OutlinesDemo".into(),
resolution_in_pixel: resolution,
view_from_world: macaw::IsoTransform::look_at_rh(
camera_position,
glam::Vec3::ZERO,
glam::Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
pixels_from_point,
outline_config: Some(OutlineConfig {
outline_radius_pixel: (seconds_since_startup * 2.0).sin().abs() * 10.0
+ 2.0,
color_layer_a: re_renderer::Rgba::from_rgb(1.0, 0.6, 0.0),
color_layer_b: re_renderer::Rgba::from_rgba_unmultiplied(
0.25, 0.3, 1.0, 0.5,
),
}),
..Default::default()
let mut view_builder = ViewBuilder::new(
re_ctx,
TargetConfiguration {
name: "OutlinesDemo".into(),
resolution_in_pixel: resolution,
view_from_world: macaw::IsoTransform::look_at_rh(
camera_position,
glam::Vec3::ZERO,
glam::Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
)
.unwrap();
pixels_from_point,
outline_config: Some(OutlineConfig {
outline_radius_pixel: (seconds_since_startup * 2.0).sin().abs() * 10.0 + 2.0,
color_layer_a: re_renderer::Rgba::from_rgb(1.0, 0.6, 0.0),
color_layer_b: re_renderer::Rgba::from_rgba_unmultiplied(0.25, 0.3, 1.0, 0.5),
}),
..Default::default()
},
);

let outline_mask_large_mesh = match ((seconds_since_startup * 0.5) as u64) % 5 {
0 => OutlineMaskPreference::NONE,
Expand Down
42 changes: 19 additions & 23 deletions crates/re_renderer/examples/picking.rs
Original file line number Diff line number Diff line change
Expand Up @@ -118,33 +118,29 @@ impl framework::Example for Picking {
}
}

let mut view_builder = ViewBuilder::default();

// TODO(#1426): unify camera logic between examples.
let camera_position = glam::vec3(1.0, 3.5, 7.0);

view_builder
.setup_view(
re_ctx,
TargetConfiguration {
name: "OutlinesDemo".into(),
resolution_in_pixel: resolution,
view_from_world: macaw::IsoTransform::look_at_rh(
camera_position,
glam::Vec3::ZERO,
glam::Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
pixels_from_point,
outline_config: None,
..Default::default()
let mut view_builder = ViewBuilder::new(
re_ctx,
TargetConfiguration {
name: "OutlinesDemo".into(),
resolution_in_pixel: resolution,
view_from_world: macaw::IsoTransform::look_at_rh(
camera_position,
glam::Vec3::ZERO,
glam::Vec3::Y,
)
.unwrap(),
projection_from_view: Projection::Perspective {
vertical_fov: 70.0 * std::f32::consts::TAU / 360.0,
near_plane_distance: 0.01,
},
)
.unwrap();
pixels_from_point,
outline_config: None,
..Default::default()
},
);

// Use an uneven number of pixels for the picking rect so that there is a clearly defined middle-pixel.
// (for this sample a size of 1 would be sufficient, but for a real application you'd want to use a larger size to allow snapping)
Expand Down
Loading

1 comment on commit fe7ac0e

@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: fe7ac0e Previous: e8e2d9b Ratio
datastore/num_rows=1000/num_instances=1000/packed=false/insert/default 2819827 ns/iter (± 142144) 2981165 ns/iter (± 108084) 0.95
datastore/num_rows=1000/num_instances=1000/packed=false/latest_at/default 371 ns/iter (± 1) 371 ns/iter (± 8) 1
datastore/num_rows=1000/num_instances=1000/packed=false/latest_at_missing/primary/default 307 ns/iter (± 0) 262 ns/iter (± 0) 1.17
datastore/num_rows=1000/num_instances=1000/packed=false/latest_at_missing/secondaries/default 431 ns/iter (± 2) 422 ns/iter (± 0) 1.02
datastore/num_rows=1000/num_instances=1000/packed=false/range/default 2917031 ns/iter (± 39259) 3017443 ns/iter (± 91276) 0.97
datastore/num_rows=1000/num_instances=1000/gc/default 2424218 ns/iter (± 8074) 2429381 ns/iter (± 6220) 1.00
mono_points_arrow/generate_message_bundles 27021462 ns/iter (± 779940) 30267924 ns/iter (± 944472) 0.89
mono_points_arrow/generate_messages 113254286 ns/iter (± 873559) 124931098 ns/iter (± 964543) 0.91
mono_points_arrow/encode_log_msg 143335168 ns/iter (± 735831) 158759587 ns/iter (± 1801739) 0.90
mono_points_arrow/encode_total 286108476 ns/iter (± 1191559) 314771503 ns/iter (± 1998647) 0.91
mono_points_arrow/decode_log_msg 177959619 ns/iter (± 698319) 188383161 ns/iter (± 2069529) 0.94
mono_points_arrow/decode_message_bundles 59357561 ns/iter (± 946158) 68310884 ns/iter (± 669304) 0.87
mono_points_arrow/decode_total 235592840 ns/iter (± 1059523) 255173400 ns/iter (± 1843914) 0.92
mono_points_arrow_batched/generate_message_bundles 21794503 ns/iter (± 938392) 22826812 ns/iter (± 1815212) 0.95
mono_points_arrow_batched/generate_messages 4290676 ns/iter (± 213744) 4458405 ns/iter (± 270867) 0.96
mono_points_arrow_batched/encode_log_msg 1376610 ns/iter (± 2566) 1341331 ns/iter (± 5088) 1.03
mono_points_arrow_batched/encode_total 27696912 ns/iter (± 1063716) 30238386 ns/iter (± 1555436) 0.92
mono_points_arrow_batched/decode_log_msg 779502 ns/iter (± 1468) 781137 ns/iter (± 2263) 1.00
mono_points_arrow_batched/decode_message_bundles 7594364 ns/iter (± 72975) 7744633 ns/iter (± 252068) 0.98
mono_points_arrow_batched/decode_total 8466092 ns/iter (± 84815) 8909336 ns/iter (± 438417) 0.95
batch_points_arrow/generate_message_bundles 193610 ns/iter (± 519) 195769 ns/iter (± 370) 0.99
batch_points_arrow/generate_messages 5089 ns/iter (± 34) 5216 ns/iter (± 28) 0.98
batch_points_arrow/encode_log_msg 259391 ns/iter (± 2214) 259608 ns/iter (± 2435) 1.00
batch_points_arrow/encode_total 489148 ns/iter (± 1640) 490557 ns/iter (± 2141) 1.00
batch_points_arrow/decode_log_msg 213390 ns/iter (± 560) 212012 ns/iter (± 821) 1.01
batch_points_arrow/decode_message_bundles 1890 ns/iter (± 10) 1904 ns/iter (± 8) 0.99
batch_points_arrow/decode_total 220726 ns/iter (± 615) 221271 ns/iter (± 860) 1.00
arrow_mono_points/insert 2301868154 ns/iter (± 5781112) 2480208955 ns/iter (± 8613831) 0.93
arrow_mono_points/query 1201539 ns/iter (± 6948) 1194269 ns/iter (± 25834) 1.01
arrow_batch_points/insert 1152832 ns/iter (± 6155) 1146727 ns/iter (± 1648) 1.01
arrow_batch_points/query 14392 ns/iter (± 103) 14649 ns/iter (± 151) 0.98
arrow_batch_vecs/insert 26380 ns/iter (± 81) 26298 ns/iter (± 70) 1.00
arrow_batch_vecs/query 325263 ns/iter (± 737) 325545 ns/iter (± 1672) 1.00
tuid/Tuid::random 34 ns/iter (± 0) 34 ns/iter (± 0) 1

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

Please sign in to comment.