[−][src]Struct city2ba::BAProblem
Bundle adjustment problem composed of cameras, points, and observations of points by cameras.
Observations are stored as an array of arrays where v[i][j] = (k, (u, v))
indicates that camera
i
sees point k
at (u, v)
in the camera frame.
Fields
cameras: Vec<C>
points: Vec<Point3<f64>>
vis_graph: Vec<Vec<(usize, (f64, f64))>>
Methods
impl<C: Camera> BAProblem<C>
[src]
pub fn total_reprojection_error(&self, norm: f64) -> f64
[src]
Amount of reprojection error in the problem. Computed as the norm
-norm of the difference
of all observed points from their projection.
pub fn mean(&self) -> Vector3<f64>
[src]
Center of mass of cameras and points.
pub fn std(&self) -> Vector3<f64>
[src]
Standard deviation of cameras and points from the center of mass.
pub fn extent(&self) -> (Vector3<f64>, Vector3<f64>)
[src]
Smallest and largest coordinates of the problem.
pub fn dimensions(&self) -> Vector3<f64>
[src]
Dimensions in x,y,z of the problem.
pub fn new(
cams: Vec<C>,
points: Vec<Point3<f64>>,
obs: Vec<(usize, usize, f64, f64)>
) -> Self
[src]
cams: Vec<C>,
points: Vec<Point3<f64>>,
obs: Vec<(usize, usize, f64, f64)>
) -> Self
Create a new bundle adjustment problem from a set a cameras, points, and observations. Observations are a tuple of camera index, point index, u, v where the camera sees the point at u,v.
pub fn from_visibility(
cams: Vec<C>,
points: Vec<Point3<f64>>,
obs: Vec<Vec<(usize, (f64, f64))>>
) -> Self
[src]
cams: Vec<C>,
points: Vec<Point3<f64>>,
obs: Vec<Vec<(usize, (f64, f64))>>
) -> Self
Create a new bundle adjustment problem from a set a cameras, points, and observations. Observations are a vector containing vectors of the points seen by the camera at the respective index.
pub fn num_points(&self) -> usize
[src]
pub fn num_cameras(&self) -> usize
[src]
pub fn num_observations(&self) -> usize
[src]
Number of camera-point observations.
impl<C: Camera + Clone> BAProblem<C>
[src]
pub fn subset(self, ci: &[usize], pi: &[usize]) -> Self
[src]
Select a subset of the problem with camera indices in ci
and point indices in pi
.
pub fn remove_singletons(self) -> Self
[src]
Remove cameras that see less than 4 points and points seen less than twice.
pub fn largest_connected_component(self) -> Self
[src]
Get the largest connected component of cameras and points.
pub fn cull(self) -> Self
[src]
Construct the largest connected component that contains cameras viewing 4 or more points and points viewed at least twice.
impl BAProblem<SnavelyCamera>
[src]
pub fn from_file_text(filepath: &Path) -> Result<Self, Error>
[src]
Parse a bundle adjustment problem from a file in the Bundle Adjustment in the Large text file format.
<num_cameras> <num_points> <num_observations>
<camera_index_1> <point_index_1> <x_1> <y_1>
...
<camera_index_num_observations> <point_index_num_observations> <x_num_observations> <y_num_observations>
<camera_1>
...
<camera_num_cameras>
<point_1>
...
<point_num_points>
where cameras are:
<R_1>
<R_2>
<R_3>
<t_1>
<t_2>
<t_3>
<focal length>
<distortion^2>
<distortion^4>
pub fn from_file_binary(filepath: &Path) -> Result<Self, Error>
[src]
Parse a bundle adjustment problem from a file in the Bundle Adjustment in the Large binary file format.
pub fn from_file(path: &Path) -> Result<Self, Error>
[src]
Parse a bundle adjustment problem from a file in the Bundle Adjustment in the Large format. Supports both binary and text formats.
pub fn write_text(&self, path: &Path) -> Result<(), Error>
[src]
Write problem in Bundle Adjustment in the Large text format.
pub fn write_binary(&self, path: &Path) -> Result<(), Error>
[src]
Write problem in Bundle Adjustment in the Large binary format.
pub fn write(&self, path: &Path) -> Result<(), Error>
[src]
Write BAProblem to a file in BAL format. Text or binary format is automatically chosen from
the filename extension. .bal
-> text, .bbal
-> binary.
Trait Implementations
impl<C: Clone + Camera> Clone for BAProblem<C>
[src]
impl<C: Debug + Camera> Debug for BAProblem<C>
[src]
impl<C> Display for BAProblem<C> where
C: Camera,
[src]
C: Camera,
Auto Trait Implementations
impl<C> RefUnwindSafe for BAProblem<C> where
C: RefUnwindSafe,
C: RefUnwindSafe,
impl<C> Send for BAProblem<C> where
C: Send,
C: Send,
impl<C> Sync for BAProblem<C> where
C: Sync,
C: Sync,
impl<C> Unpin for BAProblem<C> where
C: Unpin,
C: Unpin,
impl<C> UnwindSafe for BAProblem<C> where
C: UnwindSafe,
C: UnwindSafe,
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
SS: SubsetOf<SP>,
fn to_subset(&self) -> Option<SS>
fn is_in_subset(&self) -> bool
unsafe fn to_subset_unchecked(&self) -> SS
fn from_subset(element: &SS) -> SP
impl<T> ToOwned for T where
T: Clone,
[src]
T: Clone,
type Owned = T
The resulting type after obtaining ownership.
fn to_owned(&self) -> T
[src]
fn clone_into(&self, target: &mut T)
[src]
impl<T> ToString for T where
T: Display + ?Sized,
[src]
T: Display + ?Sized,
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,