Public Types | Private Member Functions | 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
 

Public Member Functions

Standard Constructors
 PinholeBaseK ()
 
 PinholeBaseK (const Pose3 &pose)
 
Advanced Constructors
 PinholeBaseK (const Vector &v)
 
Standard Interface
virtual ~PinholeBaseK ()
 
virtual const CALIBRATION & calibration () const =0
 return calibration More...
 
- 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=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
 
Point2 project2 (const Unit3 &point, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
 

Private Member Functions

 GTSAM_CONCEPT_MANIFOLD_TYPE (CALIBRATION)
 

Static Private Attributes

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

Transformations and measurement functions

class boost::serialization::access
 
template<class Archive >
void serialize (Archive &ar, const unsigned int)
 
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=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
 project a 3D point from world coordinates into the image More...
 
Point2 project (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) 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=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none, OptionalJacobian< 3, DimK > Dresult_dcal=boost::none) 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=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
 
double range (const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
 
double range (const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const
 
template<class CalibrationB >
double range (const PinholeBaseK< CalibrationB > &camera, OptionalJacobian< 1, 6 > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const
 

Additional Inherited Members

- 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 std::pair< size_t, size_ttranslationInterval ()
 
static Point2 Project (const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint=boost::none)
 
static Point2 Project (const Unit3 &pc, OptionalJacobian< 2, 2 > Dpoint=boost::none)
 
static Point3 BackprojectFromCamera (const Point2 &p, const double depth, OptionalJacobian< 3, 2 > Dpoint=boost::none, OptionalJacobian< 3, 1 > Ddepth=boost::none)
 backproject a 2-dimensional point to a 3-dimensional point at given depth More...
 
- 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 >

Definition at line 34 of file PinholePose.h.

Member Typedef Documentation

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

Definition at line 45 of file PinholePose.h.

Constructor & Destructor Documentation

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

default constructor

Definition at line 51 of file PinholePose.h.

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

constructor with pose

Definition at line 55 of file PinholePose.h.

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

Definition at line 63 of file PinholePose.h.

template<typename CALIBRATION>
virtual gtsam::PinholeBaseK< CALIBRATION >::~PinholeBaseK ( )
inlinevirtual

Definition at line 71 of file PinholePose.h.

Member Function Documentation

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 96 of file PinholePose.h.

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

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

Definition at line 132 of file PinholePose.h.

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.

template<typename CALIBRATION>
virtual const CALIBRATION& gtsam::PinholeBaseK< CALIBRATION >::calibration ( ) const
pure virtual
template<typename CALIBRATION>
gtsam::PinholeBaseK< CALIBRATION >::GTSAM_CONCEPT_MANIFOLD_TYPE ( CALIBRATION  )
private
template<typename CALIBRATION>
Point2 gtsam::PinholeBaseK< CALIBRATION >::project ( const Point3 pw,
OptionalJacobian< 2, 6 >  Dpose = boost::none,
OptionalJacobian< 2, 3 >  Dpoint = boost::none,
OptionalJacobian< 2, DimK Dcal = boost::none 
) const
inline

project a 3D point from world coordinates into the image

Definition at line 118 of file PinholePose.h.

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

project a point at infinity from world coordinates into the image

Definition at line 125 of file PinholePose.h.

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 82 of file PinholePose.h.

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

Calculate range to a landmark

Parameters
point3D location of landmark
Returns
range (double)

Definition at line 175 of file PinholePose.h.

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

Calculate range to another pose

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

Definition at line 186 of file PinholePose.h.

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

Calculate range to a CalibratedCamera

Parameters
cameraOther camera
Returns
range (double)

Definition at line 196 of file PinholePose.h.

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

Calculate range to a PinholePoseK derived class

Parameters
cameraOther camera
Returns
range (double)

Definition at line 207 of file PinholePose.h.

template<typename CALIBRATION>
template<class Archive >
void gtsam::PinholeBaseK< CALIBRATION >::serialize ( Archive &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 218 of file PinholePose.h.

Friends And Related Function Documentation

template<typename CALIBRATION>
friend class boost::serialization::access
friend

Serialization function

Definition at line 216 of file PinholePose.h.

Member Data Documentation

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

Definition at line 41 of file PinholePose.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:19