sophus-rs
2d and 3d geometry for Computer Vision and Robotics
Overview
sophus-rs is a Rust library for 2d and 3d geometry for Computer Vision and Robotics applications. It is a spin-off of the Sophus C++ library which focuses on Lie groups (e.g. rotations and transformations in 2d and 3d).
In addition to Lie groups, sophus-rs also includes other geometric/maths concepts.
This crates supports wasm. Check out the web-demo: https://sophus-vision.github.io/sophus-rs/. Note: The web app is based on egui and wgpu. It requires a bleeding edge browser with WebGPU support. Recent Chrome versions on MacOS, Windows and Android should work out of the box.
Automatic differentiation
sophus-rs provides an automatic differentiation using dual numbers such as [autodiff::dual::DualScalar] and [autodiff::dual::DualVector].
use *;
use ;
use VecF64;
use VectorValuedVectorMap;
// [[ x ]] [[ x / z ]]
// proj [[ y ]] = [[ ]]
// [[ z ]] [[ y / z ]]
let a = new;
// Finite difference Jacobian
let finite_diff = sym_diff_quotient_jacobian;
// Automatic differentiation Jacobian
let auto_diff =
.jacobian;
assert_abs_diff_eq!;
Note that proj_fn is a function that takes a 3D vector and returns a 2D vector.
The Jacobian of proj_fn is 2x3 matrix. When a (three dimensional) dual
vector is passed to proj_fn, then a 2d dual vector is returned. Since we are
expecting a 2x3 Jacobian, each element of the 2d dual vector must represent
3x1 Jacobian. This is why we use DualScalar<3, 1> as the scalar type.
Lie Groups
sophus-rs provides a number of Lie groups, including:
- The group of 2D rotations, [lie::Rotation2], also known as the Special Orthogonal group SO(2),
- the group of 3D rotations, [lie::Rotation3], also known as the Special Orthogonal group SO(3),
- the group of 2d isometries, [lie::Isometry2], also known as the Special Euclidean group SE(2), and
- the group of 3d isometries, [lie::Isometry3], also known as the Spevial Euclidean group SE(3).
use VecF64;
use ;
use FRAC_PI_4;
// Create a rotation around the z-axis by 45 degrees.
let world_from_foo_rotation = rot_z;
// Create a translation in 3D.
let foo_in_world = new;
// Combine them into an SE(3) transform.
let world_from_foo_isometry
= from_rotation_and_translation;
// Apply world_from_foo_isometry to a 3D point in the foo reference frame.
let point_in_foo = new;
let point_in_world = world_from_foo_isometry.transform;
// Manually compute the expected transformation:
// - rotate (10, 0, 0) around z by 45°
// - then translate by (1, 2, 3)
let angle = FRAC_PI_4;
let cos = angle.cos;
let sin = angle.sin;
let expected_point_in_world
= new;
assert_abs_diff_eq!;
// Map isometry to 6-dimensional tangent space.
let omega = world_from_foo_isometry.log;
// Map tangent space element back to the manifold.
let roundtrip_world_from_foo_isometry = exp;
assert_abs_diff_eq!;
// Compose with another isometry.
let world_from_bar_isometry = rot_y;
let bar_from_foo_isometry
= world_from_bar_isometry.inverse * world_from_foo_isometry;
Sparse non-linear least squares optimization
sophus-rs also provides a sparse non-linear least squares optimization through [crate::opt].
use *;
use ;
use DualVector;
use ;
use ;
use robust_kernel;
use ;
// We want to fit the isometry `T ∈ SE(2)` to a prior distribution
// `N(E(T), W⁻¹)`, where `E(T)` is the prior mean and `W⁻¹` is the prior
// covariance matrix.
// (1) First we define the residual cost term.
// (3) Implement the `HasResidualFn` trait for the cost term.
let prior_world_from_robot = from_translation;
// (4) Define the cost terms, by specifying the residual function
// `g(T) = Isometry2PriorCostTerm` as well as providing the prior distribution.
const POSE: &str = "poses";
let obs_pose_a_from_pose_b_poses = new;
// (5) Define the decision variables. In this case, we only have one variable,
// and we initialize it with the identity transformation.
let est_world_from_robot = identity;
let variables = new
.add_family
.build;
// (6) Perform the non-linear least squares optimization.
let solution = optimize_nlls
.unwrap;
// (7) Retrieve the refined transformation and compare it with the prior one.
let refined_world_from_robot
= solution.variables.;
assert_abs_diff_eq!;
Also check out alternative non-linear least squares crates:
And more
such unit vector, splines, image classes, camera models, and some visualization tools. Check out the documentation for more information.
Building
sophus-rs builds on stable.
[]
= "0.15.0"
To allow for batch types, such as BatchScalarF64, the 'simd' feature is required. This feature
depends on portable-simd, which is currently
only available on nightly. There
are no plans to rely on any other nightly features.
[]
= { = "0.15.0", = ["simd"] }
Crate Structure and Usage
sophus-rs is an umbrella crate that provides a single entry point to multiple
sub-crates (modules) under the sophus:: namespace. For example, the automatic differentiation
sub-crate can be accessed via use sophus::autodiff, and the lie group sub-crate via
use sophus::lie, etc.
-
If you want all of sophus’s functionalities at once (geometry, AD, manifolds, etc.), simply add
sophusin yourCargo.toml, and then in your Rust code:use *; use DualScalar; // ... -
If you only need the autodiff functionalities in isolation, you can also depend on the standalone crate underlying
sophus_autodiff.use *; use DualScalar; // ...
Status
This library is in an early development stage - hence API is highly unstable. It is likely that existing features will be removed or changed in the future.