Skip to content

Commit

Permalink
tweaks - for 0.11.0
Browse files Browse the repository at this point in the history
  • Loading branch information
strasdat committed Jan 6, 2025
1 parent ae5d375 commit b567b7c
Show file tree
Hide file tree
Showing 34 changed files with 188 additions and 219 deletions.
4 changes: 4 additions & 0 deletions crates/sophus/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,12 @@ sophus_geo.workspace = true
sophus_image.workspace = true
sophus_lie.workspace = true
sophus_opt.workspace = true
sophus_tensor.workspace = true
sophus_sensor.workspace = true
sophus_renderer.workspace = true
sophus_sim.workspace = true
sophus_spline.workspace = true
sophus_timeseries.workspace = true
sophus_viewer.workspace = true

nalgebra.workspace = true
Expand Down Expand Up @@ -50,6 +53,7 @@ std = [
"sophus_opt/std",
"sophus_sensor/std",
]
default = ["std"]

[[example]]
name = "camera_sim"
Expand Down
8 changes: 4 additions & 4 deletions crates/sophus/examples/viewer_ex.rs
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
#![cfg(feature = "std")]

use core::f64::consts::TAU;
use sophus::core::linalg::VecF64;
use sophus::autodiff::linalg::VecF64;
use sophus::examples::viewer_example::make_distorted_frame;
use sophus::lie::prelude::IsVector;
use sophus::lie::Isometry3;
use sophus::prelude::*;
use sophus::sensor::dyn_camera::DynCameraF64;
use sophus_image::intensity_image::intensity_arc_image::IsIntensityArcImage;
use sophus_image::mut_image::MutImageF32;
Expand Down Expand Up @@ -101,11 +101,11 @@ fn create_tiny_image_view_packet() -> Packet {

fn create_scene(pinhole: bool) -> Vec<Packet> {
let unified_cam = DynCameraF64::new_unified(
&VecF64::from_array([500.0, 500.0, 320.0, 240.0, 0.629, 1.02]),
VecF64::from_array([500.0, 500.0, 320.0, 240.0, 0.629, 1.02]),
ImageSize::new(639, 479),
);
let pinhole_cam = DynCameraF64::new_pinhole(
&VecF64::from_array([500.0, 500.0, 320.0, 240.0]),
VecF64::from_array([500.0, 500.0, 320.0, 240.0]),
ImageSize::new(639, 479),
);

Expand Down
10 changes: 8 additions & 2 deletions crates/sophus/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#![doc = include_str!(concat!("../", std::env!("CARGO_PKG_README")))]

#[doc(inline)]
pub use sophus_autodiff as core;
pub use sophus_autodiff as autodiff;
#[doc(inline)]
pub use sophus_geo as geo;
#[doc(inline)]
Expand All @@ -19,6 +19,12 @@ pub use sophus_sensor as sensor;
#[doc(inline)]
pub use sophus_sim as sim;
#[doc(inline)]
pub use sophus_spline as spline;
#[doc(inline)]
pub use sophus_tensor as tensor;
#[doc(inline)]
pub use sophus_timeseries as timeseries;
#[doc(inline)]
pub use sophus_viewer as viewer;

pub mod examples;
Expand All @@ -29,7 +35,7 @@ pub use nalgebra;
pub use ndarray;

pub mod prelude {
pub use crate::core::prelude::*;
pub use crate::autodiff::prelude::*;
pub use crate::image::prelude::*;
pub use crate::lie::prelude::*;
pub use crate::opt::prelude::*;
Expand Down
1 change: 1 addition & 0 deletions crates/sophus_autodiff/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -24,3 +24,4 @@ sleef = {version = "0.3", optional = true}
[features]
simd = ["sleef"]
std = []
default = ["std"]
3 changes: 3 additions & 0 deletions crates/sophus_autodiff/src/linalg/scalar.rs
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,9 @@ pub trait IsScalar<const BATCH: usize, const DM: usize, const DN: usize>:
+ AbsDiffEq<Epsilon = f64>
+ RelativeEq<Epsilon = f64>
+ IsCoreScalar
+ 'static
+ Send
+ Sync
{
/// Scalar type
type Scalar: IsScalar<BATCH, DM, DN>;
Expand Down
20 changes: 20 additions & 0 deletions crates/sophus_autodiff/src/manifold.rs
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ use crate::linalg::VecF64;
use crate::params::HasParams;
use crate::prelude::IsScalar;
extern crate alloc;
use core::fmt::Debug;

/// A tangent implementation.
pub trait IsTangent<
Expand All @@ -16,6 +17,15 @@ pub trait IsTangent<
fn tangent_examples() -> alloc::vec::Vec<S::Vector<DOF>>;
}

/// A decision variables
pub trait IsVariable: Clone + Debug + Send + Sync + 'static {
/// number of degrees of freedom
const DOF: usize;

/// update the variable in-place.
fn update(&mut self, delta: nalgebra::DVectorView<f64>);
}

/// A manifold.
pub trait IsManifold<
S: IsScalar<BATCH, DM, DN>,
Expand All @@ -41,3 +51,13 @@ impl<const N: usize> IsManifold<f64, N, N, 1, 0, 0> for VecF64<N> {
self - rhs
}
}
impl<const N: usize> IsVariable for VecF64<N> {
const DOF: usize = N;

fn update(&mut self, delta: nalgebra::DVectorView<f64>) {
assert_eq!(delta.len(), Self::DOF);
for d in 0..Self::DOF {
self[d] += delta[d];
}
}
}
5 changes: 4 additions & 1 deletion crates/sophus_geo/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,12 @@ repository.workspace = true
version.workspace = true

[dependencies]
approx.workspace = true
sophus_autodiff.workspace = true
sophus_lie.workspace = true

approx.workspace = true

[features]
simd = ["sophus_lie/simd"]
std = ["sophus_autodiff/std", "sophus_lie/std"]
default = ["std"]
1 change: 1 addition & 0 deletions crates/sophus_geo/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -13,4 +13,5 @@ pub mod unit_vector;
pub mod prelude {
pub use crate::region::IsRegion;
pub use sophus_autodiff::prelude::*;
pub use sophus_lie::prelude::*;
}
2 changes: 0 additions & 2 deletions crates/sophus_geo/src/manifold.rs

This file was deleted.

4 changes: 2 additions & 2 deletions crates/sophus_image/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@ bytemuck.workspace = true
nalgebra.workspace = true
ndarray.workspace = true
num-traits.workspace = true

tiff = {version = "0.9.0", optional = true}
png = {version ="0.17", optional = true}

[features]
simd = ["sophus_tensor/simd"]
std = ["png", "tiff", "sophus_tensor/std"]
std = ["png", "tiff", "sophus_autodiff/std", "sophus_tensor/std"]
default = ["std"]
12 changes: 6 additions & 6 deletions crates/sophus_image/src/io/tiff.rs
Original file line number Diff line number Diff line change
Expand Up @@ -109,12 +109,12 @@ pub fn load_tiff(path: impl ToString) -> std::io::Result<DynIntensityMutImage> {
));
}
// num_channels == 4
return Ok(DynIntensityMutImage::RgbaU8(
Ok(DynIntensityMutImage::RgbaU8(
MutImage4U8::make_copy_from_size_and_slice(
image_size,
bytemuck::cast_slice(&u8_img),
),
));
))
}
DecodingResult::U16(u16_img) => {
if num_channels == 1 {
Expand All @@ -139,12 +139,12 @@ pub fn load_tiff(path: impl ToString) -> std::io::Result<DynIntensityMutImage> {
));
}
// num_channels == 4
return Ok(DynIntensityMutImage::RgbaU16(
Ok(DynIntensityMutImage::RgbaU16(
MutImage4U16::make_copy_from_size_and_slice(
image_size,
bytemuck::cast_slice(&u16_img),
),
));
))
}
DecodingResult::F32(f32_img) => {
if num_channels == 1 {
Expand All @@ -169,12 +169,12 @@ pub fn load_tiff(path: impl ToString) -> std::io::Result<DynIntensityMutImage> {
));
}
// num_channels == 4
return Ok(DynIntensityMutImage::RgbaF32(
Ok(DynIntensityMutImage::RgbaF32(
MutImage4F32::make_copy_from_size_and_slice(
image_size,
bytemuck::cast_slice(&f32_img),
),
));
))
}
_ => Err(std::io::Error::other(format!(
"unsupported decoding: {:?}",
Expand Down
1 change: 1 addition & 0 deletions crates/sophus_image/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -88,5 +88,6 @@ pub mod prelude {
pub use crate::image_view::IsImageView;
pub use crate::intensity_image::dyn_intensity_image::DynIntensityMutImage;
pub use crate::mut_image_view::IsMutImageView;
pub use sophus_autodiff::prelude::*;
pub use sophus_tensor::prelude::*;
}
4 changes: 2 additions & 2 deletions crates/sophus_lie/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,15 @@ repository.workspace = true
version.workspace = true

[dependencies]
sophus_autodiff = {workspace = true}

approx.workspace = true
log.workspace = true
nalgebra.workspace = true
num-traits.workspace = true
snafu.workspace = true

sophus_autodiff = {workspace = true}

[features]
simd = ["sophus_autodiff/simd"]
std = ["sophus_autodiff/std"]
default = ["std"]
112 changes: 27 additions & 85 deletions crates/sophus_lie/src/lie_group/lie_group_manifold.rs
Original file line number Diff line number Diff line change
@@ -1,33 +1,17 @@
use sophus_autodiff::linalg::VecF64;
use sophus_autodiff::manifold::IsVariable;

use crate::lie_group::LieGroup;
use crate::prelude::*;
use crate::traits::IsLieGroupImpl;
use core::borrow::Borrow;
use core::fmt::Debug;
use sophus_autodiff::manifold::IsManifold;
use sophus_autodiff::params::HasParams;
use sophus_autodiff::params::IsParamsImpl;

extern crate alloc;

/// Left group manifold
///
/// A ⊕ t := exp(t) * A
/// A ⊖ B := log(inv(A) * B)
#[derive(Debug, Clone)]
pub struct LeftGroupManifold<
S: IsScalar<BATCH, DM, DN>,
const DOF: usize,
const PARAMS: usize,
const POINT: usize,
const AMBIENT: usize,
const BATCH: usize,
const DM: usize,
const DN: usize,
G: IsLieGroupImpl<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN>,
> {
group: LieGroup<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN, G>,
}

// Lie group as Left group manifold
//
// A ⊕ t := exp(t) * A
// A ⊖ B := log(inv(A) * B)
impl<
S: IsScalar<BATCH, DM, DN>,
const DOF: usize,
Expand All @@ -38,81 +22,39 @@ impl<
const DM: usize,
const DN: usize,
G: IsLieGroupImpl<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN> + Clone + Debug,
> IsParamsImpl<S, PARAMS, BATCH, DM, DN>
for LeftGroupManifold<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN, G>
> IsManifold<S, PARAMS, DOF, BATCH, DM, DN>
for LieGroup<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN, G>
{
fn are_params_valid<P>(params: P) -> S::Mask
where
P: for<'a> Borrow<<S as IsScalar<BATCH, DM, DN>>::Vector<PARAMS>>,
{
G::are_params_valid(params)
}

fn params_examples() -> alloc::vec::Vec<<S as IsScalar<BATCH, DM, DN>>::Vector<PARAMS>> {
G::params_examples()
fn oplus(&self, tangent: &<S as IsScalar<BATCH, DM, DN>>::Vector<DOF>) -> Self {
LieGroup::<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN, G>::exp(tangent) * self
}

fn invalid_params_examples() -> alloc::vec::Vec<<S as IsScalar<BATCH, DM, DN>>::Vector<PARAMS>>
{
G::invalid_params_examples()
fn ominus(&self, rhs: &Self) -> <S as IsScalar<BATCH, DM, DN>>::Vector<DOF> {
(self.inverse() * rhs).log()
}
}

impl<
S: IsScalar<BATCH, DM, DN>,
const DOF: usize,
const PARAMS: usize,
const POINT: usize,
const AMBIENT: usize,
const BATCH: usize,
const DM: usize,
const DN: usize,
G: IsLieGroupImpl<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN> + Clone + Debug,
> HasParams<S, PARAMS, BATCH, DM, DN>
for LeftGroupManifold<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN, G>
G: IsLieGroupImpl<f64, DOF, PARAMS, POINT, AMBIENT, 1, 0, 0>
+ Clone
+ Debug
+ Send
+ Sync
+ 'static,
> IsVariable for LieGroup<f64, DOF, PARAMS, POINT, AMBIENT, 1, 0, 0, G>
{
fn from_params<P>(params: P) -> Self
where
P: for<'a> Borrow<<S as IsScalar<BATCH, DM, DN>>::Vector<PARAMS>>,
{
Self {
group: LieGroup::from_params(params),
}
}

fn set_params<P>(&mut self, params: P)
where
P: for<'a> Borrow<<S as IsScalar<BATCH, DM, DN>>::Vector<PARAMS>>,
{
self.group.set_params(params)
}

fn params(&self) -> &<S as IsScalar<BATCH, DM, DN>>::Vector<PARAMS> {
self.group.params()
}
}
const DOF: usize = DOF;

impl<
S: IsScalar<BATCH, DM, DN>,
const DOF: usize,
const PARAMS: usize,
const POINT: usize,
const AMBIENT: usize,
const BATCH: usize,
const DM: usize,
const DN: usize,
G: IsLieGroupImpl<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN> + Clone + Debug,
> IsManifold<S, PARAMS, DOF, BATCH, DM, DN>
for LeftGroupManifold<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN, G>
{
fn oplus(&self, tangent: &<S as IsScalar<BATCH, DM, DN>>::Vector<DOF>) -> Self {
Self {
group: &LieGroup::<S, DOF, PARAMS, POINT, AMBIENT, BATCH, DM, DN, G>::exp(tangent)
* &self.group,
fn update(&mut self, delta: nalgebra::DVectorView<f64>) {
assert_eq!(delta.len(), DOF);
let mut tangent = VecF64::<DOF>::zeros();
for d in 0..DOF {
tangent[d] = delta[d];
}
}

fn ominus(&self, rhs: &Self) -> <S as IsScalar<BATCH, DM, DN>>::Vector<DOF> {
(&self.group.inverse() * &rhs.group).log()
*self = self.oplus(&tangent);
}
}
5 changes: 3 additions & 2 deletions crates/sophus_opt/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,14 @@ rayon = "1.10"
[features]
simd = [
"sophus_autodiff/simd",
"sophus_image/simd",
"sophus_lie/simd",
"sophus_sensor/simd",
"sophus_image/simd",
]
std = [
"sophus_autodiff/std",
"sophus_image/std",
"sophus_lie/std",
"sophus_sensor/std",
"sophus_image/std",
]
default = ["std"]
Loading

0 comments on commit b567b7c

Please sign in to comment.