g2o
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Protected Attributes | List of all members
g2o::ParameterCamera Class Reference

parameters for a camera More...

#include <parameter_camera.h>

Inheritance diagram for g2o::ParameterCamera:
Inheritance graph
[legend]
Collaboration diagram for g2o::ParameterCamera:
Collaboration graph
[legend]

Public Member Functions

 ParameterCamera ()
 
void setKcam (double fx, double fy, double cx, double cy)
 
void setOffset (const Isometry3 &offset_=Isometry3::Identity())
 
virtual bool read (std::istream &is)
 read the data from a stream
 
virtual bool write (std::ostream &os) const
 write the data to a stream
 
const Matrix3Kcam () const
 
const Matrix3invKcam () const
 
const Matrix3Kcam_inverseOffsetR () const
 
- Public Member Functions inherited from g2o::ParameterSE3Offset
 ParameterSE3Offset ()
 
void setOffset (const Isometry3 &offset_=Isometry3::Identity())
 
const Isometry3offset () const
 rotation of the offset as 3x3 rotation matrix
 
const Isometry3inverseOffset () const
 rotation of the inverse offset as 3x3 rotation matrix
 
- Public Member Functions inherited from g2o::Parameter
 Parameter ()
 
virtual ~Parameter ()
 
int id () const
 
void setId (int id_)
 
virtual HyperGraph::HyperGraphElementType elementType () const
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
- Public Attributes inherited from g2o::ParameterSE3Offset
 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Protected Attributes

Matrix3 _Kcam
 
Matrix3 _invKcam
 
Matrix3 _Kcam_inverseOffsetR
 
- Protected Attributes inherited from g2o::ParameterSE3Offset
Isometry3 _offset
 
Isometry3 _inverseOffset
 
- Protected Attributes inherited from g2o::Parameter
int _id
 

Detailed Description

parameters for a camera

Definition at line 38 of file parameter_camera.h.

Constructor & Destructor Documentation

◆ ParameterCamera()

g2o::ParameterCamera::ParameterCamera ( )

Definition at line 41 of file parameter_camera.cpp.

41 {
42 setId(-1);
43 setKcam(1, 1, 0.5, 0.5);
44 setOffset();
45}
void setKcam(double fx, double fy, double cx, double cy)
void setOffset(const Isometry3 &offset_=Isometry3::Identity())
void setId(int id_)
Definition parameter.cpp:33

References g2o::Parameter::setId(), setKcam(), and setOffset().

Member Function Documentation

◆ invKcam()

const Matrix3 & g2o::ParameterCamera::invKcam ( ) const
inline

◆ Kcam()

const Matrix3 & g2o::ParameterCamera::Kcam ( ) const
inline

Definition at line 48 of file parameter_camera.h.

48{ return _Kcam; }

Referenced by g2o::CacheCamera::updateImpl().

◆ Kcam_inverseOffsetR()

const Matrix3 & g2o::ParameterCamera::Kcam_inverseOffsetR ( ) const
inline

◆ read()

bool g2o::ParameterCamera::read ( std::istream &  is)
virtual

read the data from a stream

Reimplemented from g2o::ParameterSE3Offset.

Reimplemented in g2o::ParameterStereoCamera.

Definition at line 63 of file parameter_camera.cpp.

63 {
64 Vector7 off;
65 internal::readVector(is, off);
66 // normalize the quaternion to recover numerical precision lost by storing as
67 // human readable text
68 Vector4::MapType(off.data() + 3).normalize();
70 double fx, fy, cx, cy;
71 is >> fx >> fy >> cx >> cy;
72 setKcam(fx, fy, cx, cy);
73 return is.good();
74}
Isometry3 fromVectorQT(const Vector7 &v)
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Definition io_helper.h:42
VectorN< 7 > Vector7
Definition eigen_types.h:54

References g2o::internal::fromVectorQT(), g2o::internal::readVector(), setKcam(), and setOffset().

Referenced by g2o::ParameterStereoCamera::read().

◆ setKcam()

void g2o::ParameterCamera::setKcam ( double  fx,
double  fy,
double  cx,
double  cy 
)

Definition at line 52 of file parameter_camera.cpp.

52 {
53 _Kcam.setZero();
54 _Kcam(0, 0) = fx;
55 _Kcam(1, 1) = fy;
56 _Kcam(0, 2) = cx;
57 _Kcam(1, 2) = cy;
58 _Kcam(2, 2) = 1.0;
59 _invKcam = _Kcam.inverse();
61}
const Isometry3 & inverseOffset() const
rotation of the inverse offset as 3x3 rotation matrix

References _invKcam, _Kcam, _Kcam_inverseOffsetR, and g2o::ParameterSE3Offset::inverseOffset().

Referenced by main(), ParameterCamera(), and read().

◆ setOffset()

void g2o::ParameterCamera::setOffset ( const Isometry3 offset_ = Isometry3::Identity())

Definition at line 47 of file parameter_camera.cpp.

47 {
50}
void setOffset(const Isometry3 &offset_=Isometry3::Identity())

References _Kcam, _Kcam_inverseOffsetR, g2o::ParameterSE3Offset::inverseOffset(), and g2o::ParameterSE3Offset::setOffset().

Referenced by ParameterCamera(), and read().

◆ write()

bool g2o::ParameterCamera::write ( std::ostream &  os) const
virtual

write the data to a stream

Reimplemented from g2o::ParameterSE3Offset.

Reimplemented in g2o::ParameterStereoCamera.

Definition at line 76 of file parameter_camera.cpp.

76 {
78 os << _Kcam(0, 0) << " ";
79 os << _Kcam(1, 1) << " ";
80 os << _Kcam(0, 2) << " ";
81 os << _Kcam(1, 2) << " ";
82 return os.good();
83}
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
Definition io_helper.h:36
Vector7 toVectorQT(const Isometry3 &t)

References _Kcam, g2o::ParameterSE3Offset::_offset, g2o::internal::toVectorQT(), and g2o::internal::writeVector().

Referenced by g2o::ParameterStereoCamera::write().

Member Data Documentation

◆ _invKcam

Matrix3 g2o::ParameterCamera::_invKcam
protected

Definition at line 54 of file parameter_camera.h.

Referenced by setKcam().

◆ _Kcam

Matrix3 g2o::ParameterCamera::_Kcam
protected

Definition at line 53 of file parameter_camera.h.

Referenced by setKcam(), setOffset(), and write().

◆ _Kcam_inverseOffsetR

Matrix3 g2o::ParameterCamera::_Kcam_inverseOffsetR
protected

Definition at line 55 of file parameter_camera.h.

Referenced by setKcam(), and setOffset().

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::ParameterCamera::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 40 of file parameter_camera.h.


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