Public Types | Static Private Attributes | List of all members
gtsam::PinholeBaseK< CALIBRATION > Class Template Referenceabstract

#include <PinholePose.h>

Inheritance diagram for gtsam::PinholeBaseK< CALIBRATION >:
Inheritance graph
[legend]

Public Types

typedef CALIBRATION CalibrationType
 
- Public Types inherited from gtsam::PinholeBase
typedef Point2 Measurement
 
typedef Point2Vector MeasurementVector
 
typedef Rot3 Rotation
 
typedef Point3 Translation
 

Static Private Attributes

static const int DimK = FixedDimension<CALIBRATION>::value
 

Standard Constructors

 PinholeBaseK ()
 
 PinholeBaseK (const Pose3 &pose)
 

Advanced Constructors

 PinholeBaseK (const Vector &v)
 

Standard Interface

virtual const CALIBRATION & calibration () const =0
 return calibration More...
 

Transformations and measurement functions

std::pair< Point2, bool > projectSafe (const Point3 &pw) const
 Project a point into the image and check depth. More...
 
template<class POINT >
Point2 _project (const POINT &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint, OptionalJacobian< 2, DimK > Dcal) const
 
Point2 project (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
 project a 3D point from world coordinates into the image More...
 
Point2 reprojectionError (const Point3 &pw, const Point2 &measured, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
 project a 3D point from world coordinates into the image More...
 
Point2 project (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
 project a point at infinity from world coordinates into the image More...
 
Point3 backproject (const Point2 &p, double depth, OptionalJacobian< 3, 6 > Dresult_dpose={}, OptionalJacobian< 3, 2 > Dresult_dp={}, OptionalJacobian< 3, 1 > Dresult_ddepth={}, OptionalJacobian< 3, DimK > Dresult_dcal={}) const
 backproject a 2-dimensional point to a 3-dimensional point at given depth More...
 
Unit3 backprojectPointAtInfinity (const Point2 &p) const
 backproject a 2-dimensional point to a 3-dimensional point at infinity More...
 
double range (const Point3 &point, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const
 
double range (const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const
 
double range (const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const
 
template<class CalibrationB >
double range (const PinholeBaseK< CalibrationB > &camera, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const
 

Additional Inherited Members

- Public Member Functions inherited from gtsam::PinholeBase
 PinholeBase ()
 Default constructor. More...
 
 PinholeBase (const Pose3 &pose)
 Constructor with pose. More...
 
 PinholeBase (const Vector &v)
 
virtual ~PinholeBase ()=default
 Default destructor. More...
 
bool equals (const PinholeBase &camera, double tol=1e-9) const
 assert equality up to a tolerance More...
 
virtual void print (const std::string &s="PinholeBase") const
 print More...
 
const Pose3pose () const
 return pose, constant version More...
 
const Rot3rotation () const
 get rotation More...
 
const Point3translation () const
 get translation More...
 
const Pose3getPose (OptionalJacobian< 6, 6 > H) const
 return pose, with derivative More...
 
std::pair< Point2, bool > projectSafe (const Point3 &pw) const
 Project a point into the image and check depth. More...
 
Point2 project2 (const Point3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const
 
Point2 project2 (const Unit3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const
 
- Static Public Member Functions inherited from gtsam::PinholeBase
static Pose3 LevelPose (const Pose2 &pose2, double height)
 
static Pose3 LookatPose (const Point3 &eye, const Point3 &target, const Point3 &upVector)
 
static Point2 Project (const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint={})
 
static Point2 Project (const Unit3 &pc, OptionalJacobian< 2, 2 > Dpoint={})
 
static Point3 BackprojectFromCamera (const Point2 &p, const double depth, OptionalJacobian< 3, 2 > Dpoint={}, OptionalJacobian< 3, 1 > Ddepth={})
 backproject a 2-dimensional point to a 3-dimensional point at given depth More...
 
static std::pair< size_t, size_ttranslationInterval ()
 
- Static Protected Member Functions inherited from gtsam::PinholeBase
static Matrix26 Dpose (const Point2 &pn, double d)
 
static Matrix23 Dpoint (const Point2 &pn, double d, const Matrix3 &Rt)
 

Detailed Description

template<typename CALIBRATION>
class gtsam::PinholeBaseK< CALIBRATION >

A pinhole camera class that has a Pose3 and a fixed Calibration.

Definition at line 33 of file PinholePose.h.

Member Typedef Documentation

◆ CalibrationType

template<typename CALIBRATION >
typedef CALIBRATION gtsam::PinholeBaseK< CALIBRATION >::CalibrationType

Definition at line 44 of file PinholePose.h.

Constructor & Destructor Documentation

◆ PinholeBaseK() [1/3]

template<typename CALIBRATION >
gtsam::PinholeBaseK< CALIBRATION >::PinholeBaseK ( )
inline

default constructor

Definition at line 50 of file PinholePose.h.

◆ PinholeBaseK() [2/3]

template<typename CALIBRATION >
gtsam::PinholeBaseK< CALIBRATION >::PinholeBaseK ( const Pose3 pose)
inlineexplicit

constructor with pose

Definition at line 54 of file PinholePose.h.

◆ PinholeBaseK() [3/3]

template<typename CALIBRATION >
gtsam::PinholeBaseK< CALIBRATION >::PinholeBaseK ( const Vector v)
inlineexplicit

Definition at line 62 of file PinholePose.h.

Member Function Documentation

◆ _project()

template<typename CALIBRATION >
template<class POINT >
Point2 gtsam::PinholeBaseK< CALIBRATION >::_project ( const POINT &  pw,
OptionalJacobian< 2, 6 >  Dpose,
OptionalJacobian< 2, FixedDimension< POINT >::value >  Dpoint,
OptionalJacobian< 2, DimK Dcal 
) const
inline

Templated projection of a point (possibly at infinity) from world coordinate to the image

Parameters
pwis a 3D point or a Unit3 (point at infinity) in world coordinates
Dposeis the Jacobian w.r.t. pose3
Dpointis the Jacobian w.r.t. point3
Dcalis the Jacobian w.r.t. calibration

Definition at line 90 of file PinholePose.h.

◆ backproject()

template<typename CALIBRATION >
Point3 gtsam::PinholeBaseK< CALIBRATION >::backproject ( const Point2 p,
double  depth,
OptionalJacobian< 3, 6 >  Dresult_dpose = {},
OptionalJacobian< 3, 2 >  Dresult_dp = {},
OptionalJacobian< 3, 1 >  Dresult_ddepth = {},
OptionalJacobian< 3, DimK Dresult_dcal = {} 
) const
inline

backproject a 2-dimensional point to a 3-dimensional point at given depth

Definition at line 133 of file PinholePose.h.

◆ backprojectPointAtInfinity()

template<typename CALIBRATION >
Unit3 gtsam::PinholeBaseK< CALIBRATION >::backprojectPointAtInfinity ( const Point2 p) const
inline

backproject a 2-dimensional point to a 3-dimensional point at infinity

Definition at line 164 of file PinholePose.h.

◆ calibration()

template<typename CALIBRATION >
virtual const CALIBRATION& gtsam::PinholeBaseK< CALIBRATION >::calibration ( ) const
pure virtual

◆ project() [1/2]

template<typename CALIBRATION >
Point2 gtsam::PinholeBaseK< CALIBRATION >::project ( const Point3 pw,
OptionalJacobian< 2, 6 >  Dpose = {},
OptionalJacobian< 2, 3 >  Dpoint = {},
OptionalJacobian< 2, DimK Dcal = {} 
) const
inline

project a 3D point from world coordinates into the image

Definition at line 112 of file PinholePose.h.

◆ project() [2/2]

template<typename CALIBRATION >
Point2 gtsam::PinholeBaseK< CALIBRATION >::project ( const Unit3 pw,
OptionalJacobian< 2, 6 >  Dpose = {},
OptionalJacobian< 2, 2 >  Dpoint = {},
OptionalJacobian< 2, DimK Dcal = {} 
) const
inline

project a point at infinity from world coordinates into the image

Definition at line 126 of file PinholePose.h.

◆ projectSafe()

template<typename CALIBRATION >
std::pair<Point2, bool> gtsam::PinholeBaseK< CALIBRATION >::projectSafe ( const Point3 pw) const
inline

Project a point into the image and check depth.

Definition at line 76 of file PinholePose.h.

◆ range() [1/4]

template<typename CALIBRATION >
double gtsam::PinholeBaseK< CALIBRATION >::range ( const CalibratedCamera camera,
OptionalJacobian< 1, 6 >  Dcamera = {},
OptionalJacobian< 1, 6 >  Dother = {} 
) const
inline

Calculate range to a CalibratedCamera

Parameters
cameraOther camera
Returns
range (double)

Definition at line 196 of file PinholePose.h.

◆ range() [2/4]

template<typename CALIBRATION >
template<class CalibrationB >
double gtsam::PinholeBaseK< CALIBRATION >::range ( const PinholeBaseK< CalibrationB > &  camera,
OptionalJacobian< 1, 6 >  Dcamera = {},
OptionalJacobian< 1, 6 >  Dother = {} 
) const
inline

Calculate range to a PinholePoseK derived class

Parameters
cameraOther camera
Returns
range (double)

Definition at line 207 of file PinholePose.h.

◆ range() [3/4]

template<typename CALIBRATION >
double gtsam::PinholeBaseK< CALIBRATION >::range ( const Point3 point,
OptionalJacobian< 1, 6 >  Dcamera = {},
OptionalJacobian< 1, 3 >  Dpoint = {} 
) const
inline

Calculate range to a landmark

Parameters
point3D location of landmark
Returns
range (double)

Definition at line 175 of file PinholePose.h.

◆ range() [4/4]

template<typename CALIBRATION >
double gtsam::PinholeBaseK< CALIBRATION >::range ( const Pose3 pose,
OptionalJacobian< 1, 6 >  Dcamera = {},
OptionalJacobian< 1, 6 >  Dpose = {} 
) const
inline

Calculate range to another pose

Parameters
poseOther SO(3) pose
Returns
range (double)

Definition at line 186 of file PinholePose.h.

◆ reprojectionError()

template<typename CALIBRATION >
Point2 gtsam::PinholeBaseK< CALIBRATION >::reprojectionError ( const Point3 pw,
const Point2 measured,
OptionalJacobian< 2, 6 >  Dpose = {},
OptionalJacobian< 2, 3 >  Dpoint = {},
OptionalJacobian< 2, DimK Dcal = {} 
) const
inline

project a 3D point from world coordinates into the image

Definition at line 119 of file PinholePose.h.

Member Data Documentation

◆ DimK

template<typename CALIBRATION >
const int gtsam::PinholeBaseK< CALIBRATION >::DimK = FixedDimension<CALIBRATION>::value
staticprivate

Definition at line 40 of file PinholePose.h.


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


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:18:02