Private Attributes | List of all members
gtsam::InvDepthCamera3< CALIBRATION > Class Template Reference

#include <InvDepthCamera3.h>

Private Attributes

boost::shared_ptr< CALIBRATION > k_
 The fixed camera calibration. More...
 
Pose3 pose_
 The camera pose. More...
 

Standard Constructors

 InvDepthCamera3 ()
 
 InvDepthCamera3 (const Pose3 &pose, const boost::shared_ptr< CALIBRATION > &k)
 

Standard Interface

virtual ~InvDepthCamera3 ()
 
Pose3pose ()
 return pose More...
 
const boost::shared_ptr< CALIBRATION > & calibration () const
 return calibration More...
 
void print (const std::string &s="") const
 print More...
 
gtsam::Point2 project (const Vector5 &pw, double rho, boost::optional< gtsam::Matrix & > H1=boost::none, boost::optional< gtsam::Matrix & > H2=boost::none, boost::optional< gtsam::Matrix & > H3=boost::none) const
 
std::pair< Vector5, double > backproject (const gtsam::Point2 &pi, const double depth) const
 
static gtsam::Point3 invDepthTo3D (const Vector5 &pw, double rho)
 

Advanced Interface

class boost::serialization::access
 
template<class Archive >
void serialize (Archive &ar, const unsigned int)
 

Detailed Description

template<class CALIBRATION>
class gtsam::InvDepthCamera3< CALIBRATION >

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

Definition at line 31 of file InvDepthCamera3.h.

Constructor & Destructor Documentation

template<class CALIBRATION>
gtsam::InvDepthCamera3< CALIBRATION >::InvDepthCamera3 ( )
inline

default constructor

Definition at line 42 of file InvDepthCamera3.h.

template<class CALIBRATION>
gtsam::InvDepthCamera3< CALIBRATION >::InvDepthCamera3 ( const Pose3 pose,
const boost::shared_ptr< CALIBRATION > &  k 
)
inline

constructor with pose and calibration

Definition at line 45 of file InvDepthCamera3.h.

template<class CALIBRATION>
virtual gtsam::InvDepthCamera3< CALIBRATION >::~InvDepthCamera3 ( )
inlinevirtual

Definition at line 52 of file InvDepthCamera3.h.

Member Function Documentation

template<class CALIBRATION>
std::pair<Vector5, double> gtsam::InvDepthCamera3< CALIBRATION >::backproject ( const gtsam::Point2 pi,
const double  depth 
) const
inline

backproject a 2-dimensional point to an Inverse Depth landmark useful for point initialization

Definition at line 156 of file InvDepthCamera3.h.

template<class CALIBRATION>
const boost::shared_ptr<CALIBRATION>& gtsam::InvDepthCamera3< CALIBRATION >::calibration ( ) const
inline

return calibration

Definition at line 58 of file InvDepthCamera3.h.

template<class CALIBRATION>
static gtsam::Point3 gtsam::InvDepthCamera3< CALIBRATION >::invDepthTo3D ( const Vector5 &  pw,
double  rho 
)
inlinestatic

Convert an inverse depth landmark to cartesian Point3

Parameters
pwfirst five parameters (x,y,z,theta,phi) of inv depth landmark
invinverse depth
Returns
Point3

Definition at line 72 of file InvDepthCamera3.h.

template<class CALIBRATION>
Pose3& gtsam::InvDepthCamera3< CALIBRATION >::pose ( )
inline

return pose

Definition at line 55 of file InvDepthCamera3.h.

template<class CALIBRATION>
void gtsam::InvDepthCamera3< CALIBRATION >::print ( const std::string &  s = "") const
inline

print

Definition at line 61 of file InvDepthCamera3.h.

template<class CALIBRATION>
gtsam::Point2 gtsam::InvDepthCamera3< CALIBRATION >::project ( const Vector5 &  pw,
double  rho,
boost::optional< gtsam::Matrix & >  H1 = boost::none,
boost::optional< gtsam::Matrix & >  H2 = boost::none,
boost::optional< gtsam::Matrix & >  H3 = boost::none 
) const
inline

project a point from world InvDepth parameterization to the image

Parameters
pwis a point in the world coordinate
H1is the jacobian w.r.t. [pose3 calibration]
H2is the jacobian w.r.t. inv_depth_landmark

Definition at line 84 of file InvDepthCamera3.h.

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

Definition at line 178 of file InvDepthCamera3.h.

Friends And Related Function Documentation

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

Serialization function

Definition at line 176 of file InvDepthCamera3.h.

Member Data Documentation

template<class CALIBRATION>
boost::shared_ptr<CALIBRATION> gtsam::InvDepthCamera3< CALIBRATION >::k_
private

The fixed camera calibration.

Definition at line 34 of file InvDepthCamera3.h.

template<class CALIBRATION>
Pose3 gtsam::InvDepthCamera3< CALIBRATION >::pose_
private

The camera pose.

Definition at line 33 of file InvDepthCamera3.h.


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


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