gtsam 4.2
gtsam
Loading...
Searching...
No Matches
gtsam::SphericalCamera Class Reference

Detailed Description

A spherical camera class that has a Pose3 and measures bearing vectors.

The camera has an ‘Empty’ calibration and the only 6 dof are the pose

Standard Constructors

 SphericalCamera ()
 Default constructor.
 SphericalCamera (const Pose3 &pose)
 Constructor with pose.
 SphericalCamera (const Pose3 &pose, const EmptyCal::shared_ptr &cal)
 Constructor with empty intrinsics (needed for smart factors).

Advanced Constructors

 SphericalCamera (const Vector &v)
virtual ~SphericalCamera ()=default
 Default destructor.
const EmptyCal::shared_ptr & sharedCalibration () const
 return shared pointer to calibration
const EmptyCalcalibration () const
 return calibration

Testable

bool equals (const SphericalCamera &camera, double tol=1e-9) const
 assert equality up to a tolerance
virtual void print (const std::string &s="SphericalCamera") const
 print

Standard Interface

const Pose3pose () const
 return pose, constant version
const Rot3rotation () const
 get rotation
const Point3translation () const
 get translation

Transformations and measurement functions

std::pair< Unit3, bool > projectSafe (const Point3 &pw) const
 Project a point into the image and check depth.
Unit3 project2 (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
 Project point into the image (note: there is no CheiralityException for a spherical camera).
Unit3 project2 (const Unit3 &pwu, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
 Project point into the image (note: there is no CheiralityException for a spherical camera).
Point3 backproject (const Unit3 &p, const double depth) const
 backproject a 2-dimensional point to a 3-dimensional point at given depth
Unit3 backprojectPointAtInfinity (const Unit3 &p) const
 backproject point at infinity
Unit3 project (const Point3 &point, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
 Project point into the image (note: there is no CheiralityException for a spherical camera).
Vector2 reprojectionError (const Point3 &point, const Unit3 &measured, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
 Compute reprojection error for a given 3D point in world coordinates.

Public Member Functions

SphericalCamera retract (const Vector6 &d) const
 move a cameras according to d
Vector6 localCoordinates (const SphericalCamera &p) const
 return canonical coordinate
Matrix34 cameraProjectionMatrix () const
 for Linear Triangulation
Vector defaultErrorWhenTriangulatingBehindCamera () const
 for Nonlinear Triangulation
size_t dim () const

Static Public Member Functions

static SphericalCamera Identity ()
 for Canonical
static size_t Dim ()

Public Types

enum  { dimension = 6 }
using Measurement = Unit3
using MeasurementVector = std::vector<Unit3>
using CalibrationType = EmptyCal

Protected Attributes

EmptyCal::shared_ptr emptyCal_

Friends

class boost::serialization::access
 Serialization function.

Member Function Documentation

◆ Dim()

size_t gtsam::SphericalCamera::Dim ( )
inlinestatic

◆ dim()

size_t gtsam::SphericalCamera::dim ( ) const
inline

◆ project()

Unit3 gtsam::SphericalCamera::project ( const Point3 & point,
OptionalJacobian< 2, 6 > Dpose = boost::none,
OptionalJacobian< 2, 3 > Dpoint = boost::none ) const

Project point into the image (note: there is no CheiralityException for a spherical camera).

Parameters
point3D point in world coordinates
Returns
the intrinsic coordinates of the projected point

◆ project2() [1/2]

Unit3 gtsam::SphericalCamera::project2 ( const Point3 & pw,
OptionalJacobian< 2, 6 > Dpose = boost::none,
OptionalJacobian< 2, 3 > Dpoint = boost::none ) const

Project point into the image (note: there is no CheiralityException for a spherical camera).

Parameters
point3D point in world coordinates
Returns
the intrinsic coordinates of the projected point

◆ project2() [2/2]

Unit3 gtsam::SphericalCamera::project2 ( const Unit3 & pwu,
OptionalJacobian< 2, 6 > Dpose = boost::none,
OptionalJacobian< 2, 2 > Dpoint = boost::none ) const

Project point into the image (note: there is no CheiralityException for a spherical camera).

Parameters
point3D direction in world coordinates
Returns
the intrinsic coordinates of the projected point

◆ reprojectionError()

Vector2 gtsam::SphericalCamera::reprojectionError ( const Point3 & point,
const Unit3 & measured,
OptionalJacobian< 2, 6 > Dpose = boost::none,
OptionalJacobian< 2, 3 > Dpoint = boost::none ) const

Compute reprojection error for a given 3D point in world coordinates.

Parameters
point3D point in world coordinates
Returns
the tangent space error between the projection and the measurement

The documentation for this class was generated from the following files:
  • /tmp/gtsam-4.2-docs.H5EUbA/src/gtsam/geometry/SphericalCamera.h
  • /tmp/gtsam-4.2-docs.H5EUbA/src/gtsam/geometry/SphericalCamera.cpp