62 for (
int i=0; i<6; i++){
72 for (
int i=0; i<2; i++)
74 is >> _focal_length[i];
76 for (
int i=0; i<2; i++)
78 is >> _principle_point[i];
81 setEstimate(
Sim3(cam2world).inverse());
87 Sim3 cam2world(estimate().inverse());
89 for (
int i=0; i<7; i++){
92 for (
int i=0; i<2; i++)
94 os << _focal_length[i] <<
" ";
96 for (
int i=0; i<2; i++)
98 os << _principle_point[i] <<
" ";
106 for (
int i=0; i<7; i++){
113 for (
int i=0; i<7; i++)
114 for (
int j=i; j<7; j++)
127 for (
int i=0; i<7; i++)
131 for (
int i=0; i<7; i++)
132 for (
int j=i; j<7; j++){
147 for (
int i=0; i<2; i++)
152 for (
int i=0; i<2; i++)
153 for (
int j=i; j<2; j++) {
163 for (
int i=0; i<2; i++){
167 for (
int i=0; i<2; i++)
168 for (
int j=i; j<2; j++){
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSim3()
G2O_REGISTER_TYPE(VERTEX_TAG, VertexTag)
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSim3ProjectXYZ()
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual void setMeasurement(const Measurement &m)
Eigen::Matrix< double, 7, 1 > Vector7d
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
stuff to open files and other unsorted components Sim3
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (...
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
G2O_REGISTER_TYPE_GROUP(data)
Vector2D _principle_point
G2O_USE_TYPE_GROUP(slam2d)
virtual bool write(std::ostream &os) const
write the vertex to a stream
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge