Public Types | List of all members
gtsam::CalibratedCamera Class Reference

#include <CalibratedCamera.h>

Inheritance diagram for gtsam::CalibratedCamera:
Inheritance graph
[legend]

Public Types

enum  { dimension = 6 }
 
- Public Types inherited from gtsam::PinholeBase
typedef Point2 Measurement
 
typedef Point2Vector MeasurementVector
 
typedef Rot3 Rotation
 
typedef Point3 Translation
 

Public Member Functions

Standard Constructors
 CalibratedCamera ()
 default constructor More...
 
 CalibratedCamera (const Pose3 &pose)
 construct with pose More...
 
Advanced Constructors
 CalibratedCamera (const Vector &v)
 construct from vector More...
 
Standard Interface
virtual ~CalibratedCamera ()
 destructor More...
 
Transformations and measurement functions
Point2 project (const Point3 &point, OptionalJacobian< 2, 6 > Dcamera=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
 
Point3 backproject (const Point2 &pn, double depth, OptionalJacobian< 3, 6 > Dresult_dpose=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none) const
 backproject a 2-dimensional point to a 3-dimensional point at given depth 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 > H1=boost::none, OptionalJacobian< 1, 6 > H2=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 CalibratedCamera Create (const Pose3 &pose, OptionalJacobian< dimension, 6 > H1=boost::none)
 
static CalibratedCamera Level (const Pose2 &pose2, double height)
 
static CalibratedCamera Lookat (const Point3 &eye, const Point3 &target, const Point3 &upVector)
 
- 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...
 

Manifold

CalibratedCamera retract (const Vector &d) const
 move a cameras pose according to d More...
 
Vector localCoordinates (const CalibratedCamera &T2) const
 Return canonical coordinate. More...
 
void print (const std::string &s="CalibratedCamera") const override
 print More...
 
size_t dim () const
 
static size_t Dim ()
 

Advanced Interface

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

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

Definition at line 247 of file CalibratedCamera.h.

Member Enumeration Documentation

anonymous enum
Enumerator
dimension 

Definition at line 251 of file CalibratedCamera.h.

Constructor & Destructor Documentation

gtsam::CalibratedCamera::CalibratedCamera ( )
inline

default constructor

Definition at line 259 of file CalibratedCamera.h.

gtsam::CalibratedCamera::CalibratedCamera ( const Pose3 pose)
inlineexplicit

construct with pose

Definition at line 263 of file CalibratedCamera.h.

gtsam::CalibratedCamera::CalibratedCamera ( const Vector v)
inlineexplicit

construct from vector

Definition at line 303 of file CalibratedCamera.h.

virtual gtsam::CalibratedCamera::~CalibratedCamera ( )
inlinevirtual

destructor

Definition at line 312 of file CalibratedCamera.h.

Member Function Documentation

Point3 gtsam::CalibratedCamera::backproject ( const Point2 pn,
double  depth,
OptionalJacobian< 3, 6 >  Dresult_dpose = boost::none,
OptionalJacobian< 3, 2 >  Dresult_dp = boost::none,
OptionalJacobian< 3, 1 >  Dresult_ddepth = boost::none 
) const
inline

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

Definition at line 352 of file CalibratedCamera.h.

static CalibratedCamera gtsam::CalibratedCamera::Create ( const Pose3 pose,
OptionalJacobian< dimension, 6 >  H1 = boost::none 
)
inlinestatic

Definition at line 272 of file CalibratedCamera.h.

size_t gtsam::CalibratedCamera::dim ( ) const
inline
Deprecated:

Definition at line 331 of file CalibratedCamera.h.

static size_t gtsam::CalibratedCamera::Dim ( )
inlinestatic
Deprecated:

Definition at line 336 of file CalibratedCamera.h.

CalibratedCamera gtsam::CalibratedCamera::Level ( const Pose2 pose2,
double  height 
)
static

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

Parameters
pose2specifies the location and viewing direction
heightspecifies the height of the camera (along the positive Z-axis) (theta 0 = looking in direction of positive X axis)

Definition at line 177 of file CalibratedCamera.cpp.

Vector gtsam::CalibratedCamera::localCoordinates ( const CalibratedCamera T2) const

Return canonical coordinate.

Definition at line 199 of file CalibratedCamera.cpp.

CalibratedCamera gtsam::CalibratedCamera::Lookat ( const Point3 eye,
const Point3 target,
const Point3 upVector 
)
static

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

Definition at line 182 of file CalibratedCamera.cpp.

void gtsam::CalibratedCamera::print ( const std::string &  s = "CalibratedCamera") const
inlineoverridevirtual

print

Reimplemented from gtsam::PinholeBase.

Definition at line 326 of file CalibratedCamera.h.

Point2 gtsam::CalibratedCamera::project ( const Point3 point,
OptionalJacobian< 2, 6 >  Dcamera = boost::none,
OptionalJacobian< 2, 3 >  Dpoint = boost::none 
) const
Deprecated:
Use project2, which is more consistently named across Pinhole cameras

Definition at line 188 of file CalibratedCamera.cpp.

double gtsam::CalibratedCamera::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 381 of file CalibratedCamera.h.

double gtsam::CalibratedCamera::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 392 of file CalibratedCamera.h.

double gtsam::CalibratedCamera::range ( const CalibratedCamera camera,
OptionalJacobian< 1, 6 >  H1 = boost::none,
OptionalJacobian< 1, 6 >  H2 = boost::none 
) const
inline

Calculate range to another camera

Parameters
cameraOther camera
Returns
range (double)

Definition at line 402 of file CalibratedCamera.h.

CalibratedCamera gtsam::CalibratedCamera::retract ( const Vector d) const

move a cameras pose according to d

Definition at line 194 of file CalibratedCamera.cpp.

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

Definition at line 418 of file CalibratedCamera.h.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 416 of file CalibratedCamera.h.


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


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