g2o
Public Member Functions | Public Attributes | Protected Attributes | List of all members
g2o::deprecated::ParameterCamera Class Reference

parameters for a camera More...

#include <parameter_camera.h>

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

Public Member Functions

 ParameterCamera ()
 
void setKcam (double fx, double fy, double cx, double cy)
 
void setOffset (const SE3Quat &offset_=SE3Quat())
 
virtual bool read (std::istream &is)
 read the data from a stream More...
 
virtual bool write (std::ostream &os) const
 write the data to a stream More...
 
const Eigen::Matrix3d & Kcam () const
 
const Eigen::Matrix3d & invKcam () const
 
const Eigen::Matrix3d & Kcam_inverseOffsetR () const
 
- Public Member Functions inherited from g2o::deprecated::ParameterSE3Offset
 ParameterSE3Offset ()
 
void setOffset (const SE3Quat &offset_=SE3Quat())
 
const SE3Quatoffset () const
 return the offset as SE3Quat More...
 
const Eigen::Isometry3d & offsetMatrix () const
 rotation of the offset as 3x3 rotation matrix More...
 
const Eigen::Isometry3d & inverseOffsetMatrix () const
 rotation of the inverse offset as 3x3 rotation matrix More...
 
- 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 ()
 
HyperGraphElementclone () const
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
- Public Attributes inherited from g2o::deprecated::ParameterSE3Offset
 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Protected Attributes

Eigen::Matrix3d _Kcam
 
Eigen::Matrix3d _invKcam
 
Eigen::Matrix3d _Kcam_inverseOffsetR
 
- Protected Attributes inherited from g2o::deprecated::ParameterSE3Offset
SE3Quat _offset
 
Eigen::Isometry3d _offsetMatrix
 
Eigen::Isometry3d _inverseOffsetMatrix
 
- Protected Attributes inherited from g2o::Parameter
int _id
 

Detailed Description

parameters for a camera

Definition at line 41 of file parameter_camera.h.

Constructor & Destructor Documentation

g2o::deprecated::ParameterCamera::ParameterCamera ( )

Definition at line 36 of file parameter_camera.cpp.

36  {
37  setId(-1);
38  setKcam(1,1,0.5,0.5);
39  setOffset();
40  }
void setId(int id_)
Definition: parameter.cpp:35
void setKcam(double fx, double fy, double cx, double cy)
void setOffset(const SE3Quat &offset_=SE3Quat())

Member Function Documentation

const Eigen::Matrix3d& g2o::deprecated::ParameterCamera::invKcam ( ) const
inline
const Eigen::Matrix3d& g2o::deprecated::ParameterCamera::Kcam ( ) const
inline

Definition at line 51 of file parameter_camera.h.

51 { return _Kcam;}
const Eigen::Matrix3d& g2o::deprecated::ParameterCamera::Kcam_inverseOffsetR ( ) const
inline
bool g2o::deprecated::ParameterCamera::read ( std::istream &  is)
virtual

read the data from a stream

Reimplemented from g2o::deprecated::ParameterSE3Offset.

Definition at line 59 of file parameter_camera.cpp.

59  {
60  Vector7d off;
61  for (int i=0; i<7; i++)
62  is >> off[i];
63  setOffset(SE3Quat(off));
64  double fx,fy,cx,cy;
65  is >> fx >> fy >> cx >> cy;
66  setKcam(fx,fy,cx,cy);
67  return is.good();
68  }
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
void setKcam(double fx, double fy, double cx, double cy)
void setOffset(const SE3Quat &offset_=SE3Quat())
void g2o::deprecated::ParameterCamera::setKcam ( double  fx,
double  fy,
double  cx,
double  cy 
)

Definition at line 47 of file parameter_camera.cpp.

47  {
48  _Kcam.setZero();
49  _Kcam(0,0) = fx;
50  _Kcam(1,1) = fy;
51  _Kcam(0,2) = cx;
52  _Kcam(1,2) = cy;
53  _Kcam(2,2) = 1.0;
54  _invKcam = _Kcam.inverse();
56  }
const Eigen::Isometry3d & inverseOffsetMatrix() const
rotation of the inverse offset as 3x3 rotation matrix
void g2o::deprecated::ParameterCamera::setOffset ( const SE3Quat offset_ = SE3Quat())

Definition at line 42 of file parameter_camera.cpp.

42  {
45  }
const Eigen::Isometry3d & inverseOffsetMatrix() const
rotation of the inverse offset as 3x3 rotation matrix
void setOffset(const SE3Quat &offset_=SE3Quat())
bool g2o::deprecated::ParameterCamera::write ( std::ostream &  os) const
virtual

write the data to a stream

Reimplemented from g2o::deprecated::ParameterSE3Offset.

Definition at line 70 of file parameter_camera.cpp.

70  {
71  Vector7d off = offset().toVector();
72  for (int i=0; i<7; i++)
73  os << off[i] << " ";
74  os << _Kcam(0,0) << " ";
75  os << _Kcam(1,1) << " ";
76  os << _Kcam(0,2) << " ";
77  os << _Kcam(1,2) << " ";
78  return os.good();
79  }
const SE3Quat & offset() const
return the offset as SE3Quat
Vector7d toVector() const
Definition: se3quat.h:135
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35

Member Data Documentation

Eigen::Matrix3d g2o::deprecated::ParameterCamera::_invKcam
protected

Definition at line 57 of file parameter_camera.h.

Eigen::Matrix3d g2o::deprecated::ParameterCamera::_Kcam
protected

Definition at line 56 of file parameter_camera.h.

Eigen::Matrix3d g2o::deprecated::ParameterCamera::_Kcam_inverseOffsetR
protected

Definition at line 58 of file parameter_camera.h.

g2o::deprecated::ParameterCamera::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 43 of file parameter_camera.h.


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