From 9598e121955be8d7a13518fe2740f0cebf131400 Mon Sep 17 00:00:00 2001 From: Hauke Strasdat Date: Sat, 7 Dec 2024 10:07:23 -0800 Subject: [PATCH] opt: variadic macro for MakeTerm --- crates/sophus/examples/camera_sim.rs | 12 +- crates/sophus/examples/viewer_ex.rs | 18 +- crates/sophus/src/examples/viewer_example.rs | 4 +- crates/sophus/src/lib.rs | 5 +- crates/sophus_opt/src/term.rs | 375 ++++-------------- crates/sophus_sim/src/camera_simulator.rs | 4 +- crates/sophus_viewer/src/interactions.rs | 10 +- .../src/interactions/inplane_interaction.rs | 4 +- .../src/interactions/orbit_interaction.rs | 6 +- crates/sophus_viewer/src/packets.rs | 2 +- .../src/packets/scene_view_packet.rs | 2 +- crates/sophus_viewer/src/simple_viewer.rs | 2 +- crates/sophus_viewer/src/viewer_base.rs | 8 +- crates/sophus_viewer/src/views.rs | 4 +- .../src/views/active_view_info.rs | 4 +- crates/sophus_viewer/src/views/image_view.rs | 2 +- crates/sophus_viewer/src/views/plot_view.rs | 2 +- crates/sophus_viewer/src/views/scene_view.rs | 4 +- 18 files changed, 127 insertions(+), 341 deletions(-) diff --git a/crates/sophus/examples/camera_sim.rs b/crates/sophus/examples/camera_sim.rs index 25683f0..f4b07d9 100644 --- a/crates/sophus/examples/camera_sim.rs +++ b/crates/sophus/examples/camera_sim.rs @@ -1,17 +1,17 @@ #![cfg(feature = "std")] +use sophus::lie::Isometry3; +use sophus::prelude::IsImageView; +use sophus::sim::camera_simulator::CameraSimulator; +use sophus_image::io::png::save_as_png; +use sophus_image::io::tiff::save_as_tiff; +use sophus_image::ImageSize; use sophus_renderer::camera::properties::RenderCameraProperties; use sophus_renderer::renderables::color::Color; use sophus_renderer::renderables::scene_renderable::make_line3; use sophus_renderer::renderables::scene_renderable::make_mesh3_at; use sophus_renderer::renderables::scene_renderable::make_point3; use sophus_renderer::RenderContext; -use sophus::sim::camera_simulator::CameraSimulator; -use sophus_image::io::png::save_as_png; -use sophus_image::io::tiff::save_as_tiff; -use sophus_image::ImageSize; -use sophus::lie::Isometry3; -use sophus::prelude::IsImageView; pub async fn run_offscreen() { let render_state = RenderContext::new().await; diff --git a/crates/sophus/examples/viewer_ex.rs b/crates/sophus/examples/viewer_ex.rs index 0a3f6da..e16e6f7 100644 --- a/crates/sophus/examples/viewer_ex.rs +++ b/crates/sophus/examples/viewer_ex.rs @@ -1,7 +1,15 @@ #![cfg(feature = "std")] use core::f64::consts::TAU; +use sophus::core::linalg::VecF64; use sophus::examples::viewer_example::make_distorted_frame; +use sophus::lie::prelude::IsVector; +use sophus::lie::Isometry3; +use sophus::sensor::dyn_camera::DynCameraF64; +use sophus_image::intensity_image::intensity_arc_image::IsIntensityArcImage; +use sophus_image::mut_image::MutImageF32; +use sophus_image::mut_image_view::IsMutImageView; +use sophus_image::ImageSize; use sophus_renderer::camera::clipping_planes::ClippingPlanes; use sophus_renderer::camera::properties::RenderCameraProperties; use sophus_renderer::camera::RenderCamera; @@ -13,15 +21,6 @@ use sophus_renderer::renderables::scene_renderable::make_line3; use sophus_renderer::renderables::scene_renderable::make_mesh3_at; use sophus_renderer::renderables::scene_renderable::make_point3; use sophus_renderer::RenderContext; -use sophus::core::linalg::VecF64; -use sophus_image::intensity_image::intensity_arc_image::IsIntensityArcImage; -use sophus_image::mut_image::MutImageF32; -use sophus_image::mut_image_view::IsMutImageView; -use sophus_image::ImageSize; -use sophus::lie::prelude::IsVector; -use sophus::lie::Isometry3; -use sophus::sensor::dyn_camera::DynCameraF64; -use thingbuf::mpsc::blocking::channel; use sophus_viewer::packets::append_to_scene_packet; use sophus_viewer::packets::create_scene_packet; use sophus_viewer::packets::image_view_packet::ImageViewPacket; @@ -34,6 +33,7 @@ use sophus_viewer::packets::plot_view_packet::PlotViewPacket; use sophus_viewer::packets::Packet; use sophus_viewer::simple_viewer::SimpleViewer; use std::thread::spawn; +use thingbuf::mpsc::blocking::channel; fn create_distorted_image_packet() -> Packet { let mut image_packet = ImageViewPacket { diff --git a/crates/sophus/src/examples/viewer_example.rs b/crates/sophus/src/examples/viewer_example.rs index 1092057..8e387c4 100644 --- a/crates/sophus/src/examples/viewer_example.rs +++ b/crates/sophus/src/examples/viewer_example.rs @@ -1,5 +1,3 @@ -use sophus_renderer::camera::properties::RenderCameraProperties; -use sophus_renderer::renderables::frame::ImageFrame; use sophus_core::linalg::SVec; use sophus_core::linalg::VecF64; use sophus_core::prelude::IsVector; @@ -7,6 +5,8 @@ use sophus_image::arc_image::ArcImage4U8; use sophus_image::mut_image::MutImage4U8; use sophus_image::mut_image_view::IsMutImageView; use sophus_image::ImageSize; +use sophus_renderer::camera::properties::RenderCameraProperties; +use sophus_renderer::renderables::frame::ImageFrame; use sophus_sensor::dyn_camera::DynCameraF64; /// Makes example image of image-size diff --git a/crates/sophus/src/lib.rs b/crates/sophus/src/lib.rs index 8509bd0..c2aad83 100644 --- a/crates/sophus/src/lib.rs +++ b/crates/sophus/src/lib.rs @@ -11,10 +11,10 @@ pub use sophus_lie as lie; #[doc(inline)] pub use sophus_opt as opt; #[doc(inline)] -pub use sophus_sensor as sensor; -#[doc(inline)] pub use sophus_renderer as renderer; #[doc(inline)] +pub use sophus_sensor as sensor; +#[doc(inline)] pub use sophus_sim as sim; #[doc(inline)] pub use sophus_viewer as viewer; @@ -23,7 +23,6 @@ pub mod examples; pub use eframe; pub use thingbuf; - pub use nalgebra; pub use ndarray; diff --git a/crates/sophus_opt/src/term.rs b/crates/sophus_opt/src/term.rs index fb6f269..f79fe02 100644 --- a/crates/sophus_opt/src/term.rs +++ b/crates/sophus_opt/src/term.rs @@ -217,310 +217,97 @@ pub trait MakeTerm { ) -> Term; } -// TODO: Improve MakeTerm implementations: -// - Figure out how to make this work for arbitrary length tuples without code duplication. -// - Benchmark the performance the implementation against hand-written versions to rule out -// pessimization. - -impl MakeTerm for (F0,) -where - F0: FnOnce() -> MatF64, -{ - fn make_term( - self, - idx: [usize; 1], - var_kinds: [VarKind; 1], - residual: VecF64, - robust_kernel: Option, - precision_mat: Option>, - ) -> Term { - const SIZE: usize = 1; - - let residual = match robust_kernel { - Some(robust_kernel) => robust_kernel.weight(residual.norm()) * residual, - None => residual, - }; - - let maybe_dx = ( - if var_kinds[0] != VarKind::Conditioned { - Some(self.0()) +macro_rules! nested_option_tuple { + // Base case + ($var_kinds:ident; $F:ident, $D:ident, $idx:tt) => { + ( + if $var_kinds[$idx] != VarKind::Conditioned { + Some($F()) } else { None }, - (), - ); - - let dims = alloc::vec![D0]; - let mut hessian = BlockMatrix::new(&dims); - let mut gradient = BlockVector::new(&[D0]); - - let lambda_res = match precision_mat { - Some(precision_mat) => precision_mat * residual, - None => residual, - }; - - for i in 0..SIZE { - maybe_dx.set_diagonal( - 0, - i, - &lambda_res, - &mut gradient, - &mut hessian, - precision_mat, - ); - for j in i + 1..SIZE { - maybe_dx.set_off_diagonal(0, i, j, &mut hessian, precision_mat); - } - } - - Term { - hessian, - gradient, - cost: (residual.transpose() * lambda_res)[0], - idx, - num_sub_terms: 1, - } - } -} - -impl MakeTerm for (F0, F1) -where - F0: FnOnce() -> MatF64, - F1: FnOnce() -> MatF64, -{ - fn make_term( - self, - idx: [usize; 2], - var_kinds: [VarKind; 2], - residual: VecF64, - robust_kernel: Option, - precision_mat: Option>, - ) -> Term { - const SIZE: usize = 2; - - let residual = match robust_kernel { - Some(robust_kernel) => robust_kernel.weight(residual.norm()) * residual, - None => residual, - }; - - let maybe_dx = ( - if var_kinds[0] != VarKind::Conditioned { - Some(self.0()) + () + ) + }; + // Recursive case + ($var_kinds:ident; $F:ident, $D:ident, $idx:tt, $($rest:tt)*) => { + ( + if $var_kinds[$idx] != VarKind::Conditioned { + Some($F()) } else { None }, - ( - if var_kinds[1] != VarKind::Conditioned { - Some(self.1()) - } else { - None - }, - (), - ), - ); - - let dims = [D0, D1]; - let mut hessian = BlockMatrix::new(&dims); - let mut gradient = BlockVector::new(&dims); - - let lambda_res = match precision_mat { - Some(precision_mat) => precision_mat * residual, - None => residual, - }; - - for i in 0..SIZE { - maybe_dx.set_diagonal( - 0, - i, - &lambda_res, - &mut gradient, - &mut hessian, - precision_mat, - ); - for j in i + 1..SIZE { - maybe_dx.set_off_diagonal(0, i, j, &mut hessian, precision_mat); - } - } - - Term { - hessian, - gradient, - cost: (residual.transpose() * lambda_res)[0], - idx, - num_sub_terms: 1, - } - } + nested_option_tuple!($var_kinds; $($rest)*) + ) + }; } -impl MakeTerm - for (F0, F1, F2) -where - F0: FnOnce() -> MatF64, - F1: FnOnce() -> MatF64, - F2: FnOnce() -> MatF64, -{ - fn make_term( - self, - idx: [usize; 3], - var_kinds: [VarKind; 3], - residual: VecF64, - robust_kernel: Option, - precision_mat: Option>, - ) -> Term { - const SIZE: usize = 3; - - let residual = match robust_kernel { - Some(robust_kernel) => robust_kernel.weight(residual.norm()) * residual, - None => residual, - }; - - let maybe_dx = ( - if var_kinds[0] != VarKind::Conditioned { - Some(self.0()) - } else { - None - }, - ( - if var_kinds[1] != VarKind::Conditioned { - Some(self.1()) - } else { - None - }, - ( - if var_kinds[2] != VarKind::Conditioned { - Some(self.2()) - } else { - None - }, - (), - ), - ), - ); - - let dims = [D0, D1, D2]; - let mut hessian = BlockMatrix::new(&dims); - let mut gradient = BlockVector::new(&dims); - - let lambda_res = match precision_mat { - Some(precision_mat) => precision_mat * residual, - None => residual, - }; - - for i in 0..SIZE { - maybe_dx.set_diagonal( - 0, - i, - &lambda_res, - &mut gradient, - &mut hessian, - precision_mat, - ); - for j in i + 1..SIZE { - maybe_dx.set_off_diagonal(0, i, j, &mut hessian, precision_mat); +macro_rules! impl_make_term_for_tuples { + ($($N:literal: ($($F:ident, $D:ident, $idx:tt),+),)+) => { + $( + #[allow(non_snake_case)] + impl MakeTerm for ($($F,)+) + where + $( + $F: FnOnce() -> MatF64, + )+ + { + fn make_term( + self, + idx: [usize; $N], + var_kinds: [VarKind; $N], + residual: VecF64, + robust_kernel: Option, + precision_mat: Option>, + ) -> Term { + let residual = match robust_kernel { + Some(rk) => rk.weight(residual.norm()) * residual, + None => residual, + }; + + let ($($F,)+) = self; + + let maybe_dx = nested_option_tuple!(var_kinds; $($F, $D, $idx),+); + + let dims = [$($D,)+]; + let mut hessian = BlockMatrix::new(&dims); + let mut gradient = BlockVector::new(&dims); + + let lambda_res = match precision_mat { + Some(pm) => pm * residual, + None => residual, + }; + + for i in 0..$N { + maybe_dx.set_diagonal( + 0, i, &lambda_res, &mut gradient, &mut hessian, precision_mat); + for j in (i+1)..$N { + maybe_dx.set_off_diagonal(0, i, j, &mut hessian, precision_mat); + } + } + + Term { + hessian, + gradient, + cost: (residual.transpose() * lambda_res)[0], + idx, + num_sub_terms: 1, + } + } } - } - - Term { - hessian, - gradient, - cost: (residual.transpose() * lambda_res)[0], - idx, - num_sub_terms: 1, - } + )+ } } -impl< - F0, - F1, - F2, - F3, - const D0: usize, - const D1: usize, - const D2: usize, - const D3: usize, - const R: usize, - > MakeTerm for (F0, F1, F2, F3) -where - F0: FnOnce() -> MatF64, - F1: FnOnce() -> MatF64, - F2: FnOnce() -> MatF64, - F3: FnOnce() -> MatF64, -{ - fn make_term( - self, - idx: [usize; 4], - var_kinds: [VarKind; 4], - residual: VecF64, - robust_kernel: Option, - precision_mat: Option>, - ) -> Term { - const SIZE: usize = 4; - - let residual = match robust_kernel { - Some(robust_kernel) => robust_kernel.weight(residual.norm()) * residual, - None => residual, - }; - - let maybe_dx = ( - if var_kinds[0] != VarKind::Conditioned { - Some(self.0()) - } else { - None - }, - ( - if var_kinds[1] != VarKind::Conditioned { - Some(self.1()) - } else { - None - }, - ( - if var_kinds[2] != VarKind::Conditioned { - Some(self.2()) - } else { - None - }, - ( - if var_kinds[3] != VarKind::Conditioned { - Some(self.3()) - } else { - None - }, - (), - ), - ), - ), - ); - - let dims = [D0, D1, D2, D3]; - let mut hessian = BlockMatrix::new(&dims); - let mut gradient = BlockVector::new(&dims); - - let lambda_res = match precision_mat { - Some(precision_mat) => precision_mat * residual, - None => residual, - }; - - for i in 0..SIZE { - maybe_dx.set_diagonal( - 0, - i, - &lambda_res, - &mut gradient, - &mut hessian, - precision_mat, - ); - for j in i + 1..SIZE { - maybe_dx.set_off_diagonal(0, i, j, &mut hessian, precision_mat); - } - } - - Term { - hessian, - gradient, - cost: (residual.transpose() * lambda_res)[0], - idx, - num_sub_terms: 1, - } - } +// Now, just invoke the macro for all tuple sizes you need. +impl_make_term_for_tuples! { + 1: (F0,D0,0), + 2: (F0,D0,0,F1,D1,1), + 3: (F0,D0,0,F1,D1,1,F2,D2,2), + 4: (F0,D0,0,F1,D1,1,F2,D2,2,F3,D3,3), + 5: (F0,D0,0,F1,D1,1,F2,D2,2,F3,D3,3,F4,D4,4), + 6: (F0,D0,0,F1,D1,1,F2,D2,2,F3,D3,3,F4,D4,4,F5,D5,5), + 7: (F0,D0,0,F1,D1,1,F2,D2,2,F3,D3,3,F4,D4,4,F5,D5,5,F6,D6,6), + 8: (F0,D0,0,F1,D1,1,F2,D2,2,F3,D3,3,F4,D4,4,F5,D5,5,F6,D6,6,F7,D7,7), + 9: (F0,D0,0,F1,D1,1,F2,D2,2,F3,D3,3,F4,D4,4,F5,D5,5,F6,D6,6,F7,D7,7,F8,D8,7), } diff --git a/crates/sophus_sim/src/camera_simulator.rs b/crates/sophus_sim/src/camera_simulator.rs index f32a674..8723629 100644 --- a/crates/sophus_sim/src/camera_simulator.rs +++ b/crates/sophus_sim/src/camera_simulator.rs @@ -1,11 +1,11 @@ use alloc::vec::Vec; +use sophus_image::arc_image::ArcImage4U8; +use sophus_lie::Isometry3F64; use sophus_renderer::camera::properties::RenderCameraProperties; use sophus_renderer::offscreen_renderer::OffscreenRenderer; use sophus_renderer::renderables::scene_renderable::SceneRenderable; use sophus_renderer::textures::depth_image::DepthImage; use sophus_renderer::RenderContext; -use sophus_image::arc_image::ArcImage4U8; -use sophus_lie::Isometry3F64; extern crate alloc; diff --git a/crates/sophus_viewer/src/interactions.rs b/crates/sophus_viewer/src/interactions.rs index 1bd8cc6..88c4416 100644 --- a/crates/sophus_viewer/src/interactions.rs +++ b/crates/sophus_viewer/src/interactions.rs @@ -7,17 +7,17 @@ use crate::interactions::inplane_interaction::InplaneInteraction; use crate::interactions::orbit_interaction::OrbitalInteraction; use crate::preludes::*; use crate::views::ViewportSize; +use eframe::egui; +use sophus_core::linalg::VecF64; +use sophus_image::arc_image::ArcImageF32; +use sophus_image::ImageSize; +use sophus_lie::Isometry3F64; use sophus_renderer::camera::clipping_planes::ClippingPlanesF64; use sophus_renderer::camera::intrinsics::RenderIntrinsics; use sophus_renderer::renderables::color::Color; use sophus_renderer::textures::depth_image::ndc_z_to_color; use sophus_renderer::types::SceneFocusMarker; use sophus_renderer::types::TranslationAndScaling; -use eframe::egui; -use sophus_core::linalg::VecF64; -use sophus_image::arc_image::ArcImageF32; -use sophus_image::ImageSize; -use sophus_lie::Isometry3F64; /// Viewport scale pub struct ViewportScale { diff --git a/crates/sophus_viewer/src/interactions/inplane_interaction.rs b/crates/sophus_viewer/src/interactions/inplane_interaction.rs index 922067c..b58d392 100644 --- a/crates/sophus_viewer/src/interactions/inplane_interaction.rs +++ b/crates/sophus_viewer/src/interactions/inplane_interaction.rs @@ -1,13 +1,13 @@ use crate::interactions::SceneFocus; use crate::interactions::ViewportScale; use crate::preludes::*; -use sophus_renderer::camera::intrinsics::RenderIntrinsics; -use sophus_renderer::types::TranslationAndScaling; use eframe::egui; use sophus_core::linalg::VecF64; use sophus_image::ImageSize; use sophus_lie::Isometry3; use sophus_lie::Isometry3F64; +use sophus_renderer::camera::intrinsics::RenderIntrinsics; +use sophus_renderer::types::TranslationAndScaling; #[derive(Clone, Copy)] pub(crate) struct InplaneScrollState {} diff --git a/crates/sophus_viewer/src/interactions/orbit_interaction.rs b/crates/sophus_viewer/src/interactions/orbit_interaction.rs index 16fe465..645c764 100644 --- a/crates/sophus_viewer/src/interactions/orbit_interaction.rs +++ b/crates/sophus_viewer/src/interactions/orbit_interaction.rs @@ -1,9 +1,6 @@ use crate::interactions::SceneFocus; use crate::interactions::ViewportScale; use crate::preludes::*; -use sophus_renderer::camera::clipping_planes::ClippingPlanesF64; -use sophus_renderer::camera::intrinsics::RenderIntrinsics; -use sophus_renderer::types::TranslationAndScaling; use eframe::egui; use sophus_core::linalg::VecF64; use sophus_core::IsTensorLike; @@ -13,6 +10,9 @@ use sophus_image::ImageSize; use sophus_lie::traits::IsTranslationProductGroup; use sophus_lie::Isometry3; use sophus_lie::Isometry3F64; +use sophus_renderer::camera::clipping_planes::ClippingPlanesF64; +use sophus_renderer::camera::intrinsics::RenderIntrinsics; +use sophus_renderer::types::TranslationAndScaling; #[derive(Clone, Copy)] pub(crate) struct OrbitalPointerState { diff --git a/crates/sophus_viewer/src/packets.rs b/crates/sophus_viewer/src/packets.rs index 4979855..4cf5d14 100644 --- a/crates/sophus_viewer/src/packets.rs +++ b/crates/sophus_viewer/src/packets.rs @@ -4,11 +4,11 @@ use crate::packets::scene_view_packet::SceneViewCreation; use crate::packets::scene_view_packet::SceneViewPacket; use crate::packets::scene_view_packet::SceneViewPacketContent; use crate::preludes::*; +use sophus_lie::Isometry3F64; use sophus_renderer::camera::RenderCamera; use sophus_renderer::renderables::frame::ImageFrame; use sophus_renderer::renderables::pixel_renderable::PixelRenderable; use sophus_renderer::renderables::scene_renderable::SceneRenderable; -use sophus_lie::Isometry3F64; /// image packet pub mod image_view_packet; diff --git a/crates/sophus_viewer/src/packets/scene_view_packet.rs b/crates/sophus_viewer/src/packets/scene_view_packet.rs index f6330fd..3e0bab2 100644 --- a/crates/sophus_viewer/src/packets/scene_view_packet.rs +++ b/crates/sophus_viewer/src/packets/scene_view_packet.rs @@ -1,7 +1,7 @@ use crate::preludes::*; +use sophus_lie::Isometry3F64; use sophus_renderer::camera::RenderCamera; use sophus_renderer::renderables::scene_renderable::SceneRenderable; -use sophus_lie::Isometry3F64; /// Content of a scene view packet #[derive(Clone, Debug)] diff --git a/crates/sophus_viewer/src/simple_viewer.rs b/crates/sophus_viewer/src/simple_viewer.rs index e97aa87..7fbb352 100644 --- a/crates/sophus_viewer/src/simple_viewer.rs +++ b/crates/sophus_viewer/src/simple_viewer.rs @@ -2,8 +2,8 @@ use crate::packets::Packet; use crate::preludes::*; use crate::viewer_base::ViewerBase; use crate::viewer_base::ViewerBaseConfig; -use sophus_renderer::RenderContext; use eframe::egui; +use sophus_renderer::RenderContext; use thingbuf::mpsc::blocking::Receiver; /// Simple viewer diff --git a/crates/sophus_viewer/src/viewer_base.rs b/crates/sophus_viewer/src/viewer_base.rs index 3ae6b21..a66b584 100644 --- a/crates/sophus_viewer/src/viewer_base.rs +++ b/crates/sophus_viewer/src/viewer_base.rs @@ -17,19 +17,19 @@ use alloc::format; use alloc::string::String; use alloc::vec; use alloc::vec::Vec; -use sophus_renderer::aspect_ratio::HasAspectRatio; -use sophus_renderer::renderables::color::Color; -use sophus_renderer::RenderContext; use eframe::egui; use eframe::egui::Ui; use egui_plot::LineStyle; use egui_plot::PlotUi; use egui_plot::VLine; use linked_hash_map::LinkedHashMap; +use sophus_core::prelude::HasParams; use sophus_image::arc_image::ArcImageF32; use sophus_image::ImageSize; -use sophus_core::prelude::HasParams; use sophus_lie::prelude::IsTranslationProductGroup; +use sophus_renderer::aspect_ratio::HasAspectRatio; +use sophus_renderer::renderables::color::Color; +use sophus_renderer::RenderContext; use thingbuf::mpsc::blocking::Receiver; extern crate alloc; diff --git a/crates/sophus_viewer/src/views.rs b/crates/sophus_viewer/src/views.rs index cb3520f..25a8653 100644 --- a/crates/sophus_viewer/src/views.rs +++ b/crates/sophus_viewer/src/views.rs @@ -14,10 +14,10 @@ use crate::views::scene_view::SceneView; use alloc::string::String; use alloc::string::ToString; use alloc::vec::Vec; -use sophus_renderer::aspect_ratio::HasAspectRatio; -use sophus_renderer::camera::properties::RenderCameraProperties; use linked_hash_map::LinkedHashMap; use sophus_image::ImageSize; +use sophus_renderer::aspect_ratio::HasAspectRatio; +use sophus_renderer::camera::properties::RenderCameraProperties; extern crate alloc; diff --git a/crates/sophus_viewer/src/views/active_view_info.rs b/crates/sophus_viewer/src/views/active_view_info.rs index 8772e76..47f0e4d 100644 --- a/crates/sophus_viewer/src/views/active_view_info.rs +++ b/crates/sophus_viewer/src/views/active_view_info.rs @@ -1,8 +1,8 @@ use crate::preludes::*; -use sophus_renderer::camera::properties::RenderCameraProperties; -use sophus_renderer::types::SceneFocusMarker; use sophus_image::ImageSize; use sophus_lie::Isometry3F64; +use sophus_renderer::camera::properties::RenderCameraProperties; +use sophus_renderer::types::SceneFocusMarker; /// active view info pub struct ActiveViewInfo { diff --git a/crates/sophus_viewer/src/views/image_view.rs b/crates/sophus_viewer/src/views/image_view.rs index 2997c71..d6a1cb4 100644 --- a/crates/sophus_viewer/src/views/image_view.rs +++ b/crates/sophus_viewer/src/views/image_view.rs @@ -3,11 +3,11 @@ use crate::interactions::InteractionEnum; use crate::packets::image_view_packet::ImageViewPacket; use crate::preludes::*; use crate::views::View; +use linked_hash_map::LinkedHashMap; use sophus_renderer::aspect_ratio::HasAspectRatio; use sophus_renderer::camera::intrinsics::RenderIntrinsics; use sophus_renderer::offscreen_renderer::OffscreenRenderer; use sophus_renderer::RenderContext; -use linked_hash_map::LinkedHashMap; pub(crate) struct ImageView { pub(crate) renderer: OffscreenRenderer, diff --git a/crates/sophus_viewer/src/views/plot_view.rs b/crates/sophus_viewer/src/views/plot_view.rs index 0e9d29c..3cd0566 100644 --- a/crates/sophus_viewer/src/views/plot_view.rs +++ b/crates/sophus_viewer/src/views/plot_view.rs @@ -8,8 +8,8 @@ use crate::packets::plot_view_packet::CurveTrait; use crate::packets::plot_view_packet::PlotViewPacket; use crate::preludes::*; use crate::views::View; -use sophus_renderer::aspect_ratio::HasAspectRatio; use linked_hash_map::LinkedHashMap; +use sophus_renderer::aspect_ratio::HasAspectRatio; pub(crate) struct PlotView { pub(crate) enabled: bool, diff --git a/crates/sophus_viewer/src/views/scene_view.rs b/crates/sophus_viewer/src/views/scene_view.rs index 4b1cfed..48cc634 100644 --- a/crates/sophus_viewer/src/views/scene_view.rs +++ b/crates/sophus_viewer/src/views/scene_view.rs @@ -5,12 +5,12 @@ use crate::packets::scene_view_packet::SceneViewPacket; use crate::packets::scene_view_packet::SceneViewPacketContent; use crate::preludes::*; use crate::views::View; +use linked_hash_map::LinkedHashMap; +use log::warn; use sophus_renderer::aspect_ratio::HasAspectRatio; use sophus_renderer::camera::intrinsics::RenderIntrinsics; use sophus_renderer::offscreen_renderer::OffscreenRenderer; use sophus_renderer::RenderContext; -use linked_hash_map::LinkedHashMap; -use log::warn; pub(crate) struct SceneView { pub(crate) renderer: OffscreenRenderer,