Public Types | Private Types | Private Member Functions | Private Attributes | Friends | List of all members
gtsam::PinholePose< CALIBRATION > Class Template Reference

#include <PinholePose.h>

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

Public Types

enum  { dimension = 6 }
 
- Public Types inherited from gtsam::PinholeBaseK< CALIBRATION >
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
 PinholePose ()
 
 PinholePose (const Pose3 &pose)
 
 PinholePose (const Pose3 &pose, const boost::shared_ptr< CALIBRATION > &K)
 
Advanced Constructors
 PinholePose (const Vector &v)
 Init from 6D vector. More...
 
 PinholePose (const Vector &v, const Vector &K)
 Init from Vector and calibration. More...
 
 PinholePose (const Pose3 &pose, const Vector &K)
 
Standard Interface
 ~PinholePose () override
 
const boost::shared_ptr< CALIBRATION > & sharedCalibration () const
 return shared pointer to calibration More...
 
const CALIBRATION & calibration () const override
 return calibration More...
 
Point2 project2 (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
 
Point2 project2 (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
 project2 version for point at infinity More...
 
- Public Member Functions inherited from gtsam::PinholeBaseK< CALIBRATION >
 PinholeBaseK ()
 
 PinholeBaseK (const Pose3 &pose)
 
 PinholeBaseK (const Vector &v)
 
virtual ~PinholeBaseK ()
 
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
 
- 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...
 
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
 

Static Public Member Functions

Named Constructors
static PinholePose Level (const boost::shared_ptr< CALIBRATION > &K, const Pose2 &pose2, double height)
 
static PinholePose Level (const Pose2 &pose2, double height)
 PinholePose::level with default calibration. More...
 
static PinholePose Lookat (const Point3 &eye, const Point3 &target, const Point3 &upVector, const boost::shared_ptr< CALIBRATION > &K=boost::make_shared< CALIBRATION >())
 
- 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...
 

Private Types

typedef PinholeBaseK< CALIBRATION > Base
 base class has 3D pose as private member More...
 

Private Member Functions

template<class Archive >
void serialize (Archive &ar, const unsigned int)
 

Private Attributes

boost::shared_ptr< CALIBRATION > K_
 shared pointer to fixed calibration More...
 

Friends

class boost::serialization::access
 

Testable

std::ostream & operator<< (std::ostream &os, const PinholePose &camera)
 stream operator More...
 
bool equals (const Base &camera, double tol=1e-9) const
 assert equality up to a tolerance More...
 
void print (const std::string &s="PinholePose") const override
 print More...
 

Manifold

size_t dim () const
 
PinholePose retract (const Vector6 &d) const
 move a cameras according to d More...
 
Vector6 localCoordinates (const PinholePose &p) const
 return canonical coordinate More...
 
static size_t Dim ()
 
static PinholePose identity ()
 for Canonical More...
 

Additional Inherited Members

- 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::PinholePose< CALIBRATION >

Definition at line 237 of file PinholePose.h.

Member Typedef Documentation

template<typename CALIBRATION>
typedef PinholeBaseK<CALIBRATION> gtsam::PinholePose< CALIBRATION >::Base
private

base class has 3D pose as private member

Definition at line 241 of file PinholePose.h.

Member Enumeration Documentation

template<typename CALIBRATION>
anonymous enum
Enumerator
dimension 

Definition at line 246 of file PinholePose.h.

Constructor & Destructor Documentation

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

default constructor

Definition at line 254 of file PinholePose.h.

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

constructor with pose, uses default calibration

Definition at line 258 of file PinholePose.h.

template<typename CALIBRATION>
gtsam::PinholePose< CALIBRATION >::PinholePose ( const Pose3 pose,
const boost::shared_ptr< CALIBRATION > &  K 
)
inline

constructor with pose and calibration

Definition at line 263 of file PinholePose.h.

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

Init from 6D vector.

Definition at line 308 of file PinholePose.h.

template<typename CALIBRATION>
gtsam::PinholePose< CALIBRATION >::PinholePose ( const Vector v,
const Vector K 
)
inline

Init from Vector and calibration.

Definition at line 313 of file PinholePose.h.

template<typename CALIBRATION>
gtsam::PinholePose< CALIBRATION >::PinholePose ( const Pose3 pose,
const Vector K 
)
inline

Definition at line 318 of file PinholePose.h.

template<typename CALIBRATION>
gtsam::PinholePose< CALIBRATION >::~PinholePose ( )
inlineoverride

Definition at line 355 of file PinholePose.h.

Member Function Documentation

template<typename CALIBRATION>
const CALIBRATION& gtsam::PinholePose< CALIBRATION >::calibration ( ) const
inlineoverridevirtual

return calibration

Implements gtsam::PinholeBaseK< CALIBRATION >.

Definition at line 364 of file PinholePose.h.

template<typename CALIBRATION>
size_t gtsam::PinholePose< CALIBRATION >::dim ( ) const
inline
Deprecated:

Definition at line 389 of file PinholePose.h.

template<typename CALIBRATION>
static size_t gtsam::PinholePose< CALIBRATION >::Dim ( )
inlinestatic
Deprecated:

Definition at line 394 of file PinholePose.h.

template<typename CALIBRATION>
bool gtsam::PinholePose< CALIBRATION >::equals ( const Base camera,
double  tol = 1e-9 
) const
inline

assert equality up to a tolerance

Definition at line 327 of file PinholePose.h.

template<typename CALIBRATION>
static PinholePose gtsam::PinholePose< CALIBRATION >::identity ( )
inlinestatic

for Canonical

Definition at line 409 of file PinholePose.h.

template<typename CALIBRATION>
static PinholePose gtsam::PinholePose< CALIBRATION >::Level ( const boost::shared_ptr< CALIBRATION > &  K,
const Pose2 pose2,
double  height 
)
inlinestatic

Create a level camera at the given 2D pose and height

Parameters
Kthe calibration
pose2specifies the location and viewing direction (theta 0 = looking in direction of positive X axis)
heightcamera height

Definition at line 278 of file PinholePose.h.

template<typename CALIBRATION>
static PinholePose gtsam::PinholePose< CALIBRATION >::Level ( const Pose2 pose2,
double  height 
)
inlinestatic

PinholePose::level with default calibration.

Definition at line 284 of file PinholePose.h.

template<typename CALIBRATION>
Vector6 gtsam::PinholePose< CALIBRATION >::localCoordinates ( const PinholePose< CALIBRATION > &  p) const
inline

return canonical coordinate

Definition at line 404 of file PinholePose.h.

template<typename CALIBRATION>
static PinholePose gtsam::PinholePose< CALIBRATION >::Lookat ( const Point3 eye,
const Point3 target,
const Point3 upVector,
const boost::shared_ptr< CALIBRATION > &  K = boost::make_shared<CALIBRATION>() 
)
inlinestatic

Create a camera at the given eye position looking at a target point in the scene with the specified up direction vector.

Parameters
eyespecifies the camera position
targetthe point to look at
upVectorspecifies the camera up direction vector, doesn't need to be on the image plane nor orthogonal to the viewing axis
Koptional calibration parameter

Definition at line 297 of file PinholePose.h.

template<typename CALIBRATION>
void gtsam::PinholePose< CALIBRATION >::print ( const std::string &  s = "PinholePose< CALIBRATION >") const
inlineoverridevirtual

print

Reimplemented from gtsam::PinholeBase.

Definition at line 343 of file PinholePose.h.

template<typename CALIBRATION>
Point2 gtsam::PinholePose< CALIBRATION >::project2 ( const Point3 pw,
OptionalJacobian< 2, 6 >  Dpose = boost::none,
OptionalJacobian< 2, 3 >  Dpoint = boost::none 
) const
inline

project a point from world coordinate to the image, 2 derivatives only

Parameters
pwis a point in world coordinates
Dposeis the Jacobian w.r.t. the whole camera (really only the pose)
Dpointis the Jacobian w.r.t. point3

Definition at line 373 of file PinholePose.h.

template<typename CALIBRATION>
Point2 gtsam::PinholePose< CALIBRATION >::project2 ( const Unit3 pw,
OptionalJacobian< 2, 6 >  Dpose = boost::none,
OptionalJacobian< 2, 2 >  Dpoint = boost::none 
) const
inline

project2 version for point at infinity

Definition at line 379 of file PinholePose.h.

template<typename CALIBRATION>
PinholePose gtsam::PinholePose< CALIBRATION >::retract ( const Vector6 &  d) const
inline

move a cameras according to d

Definition at line 399 of file PinholePose.h.

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

Definition at line 420 of file PinholePose.h.

template<typename CALIBRATION>
const boost::shared_ptr<CALIBRATION>& gtsam::PinholePose< CALIBRATION >::sharedCalibration ( ) const
inline

return shared pointer to calibration

Definition at line 359 of file PinholePose.h.

Friends And Related Function Documentation

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

Serialization function

Definition at line 418 of file PinholePose.h.

template<typename CALIBRATION>
std::ostream& operator<< ( std::ostream &  os,
const PinholePose< CALIBRATION > &  camera 
)
friend

stream operator

Definition at line 333 of file PinholePose.h.

Member Data Documentation

template<typename CALIBRATION>
boost::shared_ptr<CALIBRATION> gtsam::PinholePose< CALIBRATION >::K_
private

shared pointer to fixed calibration

Definition at line 242 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:23