Public Types | Private Attributes | List of all members
gtsam::StereoCamera Class Reference

#include <StereoCamera.h>

Public Types

enum  { dimension = 6 }
 
typedef StereoPoint2 Measurement
 
typedef StereoPoint2Vector MeasurementVector
 

Public Member Functions

Standard Constructors
 StereoCamera ()
 Default constructor allocates a calibration! More...
 
 StereoCamera (const Pose3 &leftCamPose, const Cal3_S2Stereo::shared_ptr K)
 Construct from pose and shared calibration. More...
 
const Cal3_S2Stereocalibration () const
 Return shared pointer to calibration. More...
 
Testable
void print (const std::string &s="") const
 print More...
 
bool equals (const StereoCamera &camera, double tol=1e-9) const
 equals More...
 
Standard Interface
const Pose3pose () const
 pose More...
 
double baseline () const
 baseline More...
 
StereoPoint2 project (const Point3 &point) const
 Project 3D point to StereoPoint2 (uL,uR,v) More...
 
StereoPoint2 project2 (const Point3 &point, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
 
Point3 backproject (const StereoPoint2 &z) const
 back-project a measurement More...
 
Point3 backproject2 (const StereoPoint2 &z, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
 
Deprecated
StereoPoint2 project (const Point3 &point, OptionalJacobian< 3, 6 > H1, OptionalJacobian< 3, 3 > H2={}, OptionalJacobian< 3, 0 > H3={}) const
 
Vector defaultErrorWhenTriangulatingBehindCamera () const
 for Nonlinear Triangulation More...
 

Private Attributes

Cal3_S2Stereo::shared_ptr K_
 
Pose3 leftCamPose_
 

Manifold

size_t dim () const
 Dimensionality of the tangent space. More...
 
StereoCamera retract (const Vector &v) const
 Updates a with tangent space delta. More...
 
Vector6 localCoordinates (const StereoCamera &t2) const
 Local coordinates of manifold neighborhood around current value. More...
 
static size_t Dim ()
 Dimensionality of the tangent space. More...
 

Detailed Description

A stereo camera class, parameterize by left camera pose and stereo calibration

Definition at line 47 of file StereoCamera.h.

Member Typedef Documentation

◆ Measurement

Some classes template on either PinholeCamera or StereoCamera, and this typedef informs those classes what "project" returns.

Definition at line 55 of file StereoCamera.h.

◆ MeasurementVector

Definition at line 56 of file StereoCamera.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
dimension 

Definition at line 64 of file StereoCamera.h.

Constructor & Destructor Documentation

◆ StereoCamera() [1/2]

gtsam::StereoCamera::StereoCamera ( )
inline

Default constructor allocates a calibration!

Definition at line 72 of file StereoCamera.h.

◆ StereoCamera() [2/2]

gtsam::StereoCamera::StereoCamera ( const Pose3 leftCamPose,
const Cal3_S2Stereo::shared_ptr  K 
)

Construct from pose and shared calibration.

Definition at line 26 of file StereoCamera.cpp.

Member Function Documentation

◆ backproject()

Point3 gtsam::StereoCamera::backproject ( const StereoPoint2 z) const

back-project a measurement

Definition at line 92 of file StereoCamera.cpp.

◆ backproject2()

Point3 gtsam::StereoCamera::backproject2 ( const StereoPoint2 z,
OptionalJacobian< 3, 6 >  H1 = {},
OptionalJacobian< 3, 3 >  H2 = {} 
) const

Back-project the 2D point and compute optional derivatives

Parameters
H1derivative with respect to pose
H2derivative with respect to point

Definition at line 102 of file StereoCamera.cpp.

◆ baseline()

double gtsam::StereoCamera::baseline ( ) const
inline

baseline

Definition at line 134 of file StereoCamera.h.

◆ calibration()

const Cal3_S2Stereo& gtsam::StereoCamera::calibration ( ) const
inline

Return shared pointer to calibration.

Definition at line 80 of file StereoCamera.h.

◆ defaultErrorWhenTriangulatingBehindCamera()

Vector gtsam::StereoCamera::defaultErrorWhenTriangulatingBehindCamera ( ) const
inline

for Nonlinear Triangulation

Definition at line 174 of file StereoCamera.h.

◆ dim()

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

Dimensionality of the tangent space.

Definition at line 105 of file StereoCamera.h.

◆ Dim()

static size_t gtsam::StereoCamera::Dim ( )
inlinestatic

Dimensionality of the tangent space.

Definition at line 110 of file StereoCamera.h.

◆ equals()

bool gtsam::StereoCamera::equals ( const StereoCamera camera,
double  tol = 1e-9 
) const
inline

equals

Definition at line 95 of file StereoCamera.h.

◆ localCoordinates()

Vector6 gtsam::StereoCamera::localCoordinates ( const StereoCamera t2) const
inline

Local coordinates of manifold neighborhood around current value.

Definition at line 120 of file StereoCamera.h.

◆ pose()

const Pose3& gtsam::StereoCamera::pose ( ) const
inline

pose

Definition at line 129 of file StereoCamera.h.

◆ print()

void gtsam::StereoCamera::print ( const std::string &  s = "") const
inline

print

Definition at line 89 of file StereoCamera.h.

◆ project() [1/2]

StereoPoint2 gtsam::StereoCamera::project ( const Point3 point) const

Project 3D point to StereoPoint2 (uL,uR,v)

Definition at line 32 of file StereoCamera.cpp.

◆ project() [2/2]

StereoPoint2 gtsam::StereoCamera::project ( const Point3 point,
OptionalJacobian< 3, 6 >  H1,
OptionalJacobian< 3, 3 >  H2 = {},
OptionalJacobian< 3, 0 >  H3 = {} 
) const

Project 3D point and compute optional derivatives

Deprecated:
, use project2 - this class has fixed calibration
Parameters
H1derivative with respect to pose
H2derivative with respect to point
H3IGNORED (for calibration)

Definition at line 82 of file StereoCamera.cpp.

◆ project2()

StereoPoint2 gtsam::StereoCamera::project2 ( const Point3 point,
OptionalJacobian< 3, 6 >  H1 = {},
OptionalJacobian< 3, 3 >  H2 = {} 
) const

Project 3D point and compute optional derivatives

Parameters
H1derivative with respect to pose
H2derivative with respect to point

Definition at line 37 of file StereoCamera.cpp.

◆ retract()

StereoCamera gtsam::StereoCamera::retract ( const Vector v) const
inline

Updates a with tangent space delta.

Definition at line 115 of file StereoCamera.h.

Member Data Documentation

◆ K_

Cal3_S2Stereo::shared_ptr gtsam::StereoCamera::K_
private

Definition at line 60 of file StereoCamera.h.

◆ leftCamPose_

Pose3 gtsam::StereoCamera::leftCamPose_
private

Definition at line 59 of file StereoCamera.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:10