104 const Eigen::Matrix<double, 7, 1>
error = (Sji * Si * Sj.
inverse()).log();
105 const Eigen::Vector3d phi =
error.block<3, 1>(0, 0);
106 const Eigen::Vector3d tau =
error.block<3, 1>(3, 0);
107 const double s =
error(6);
109 const Eigen::Matrix<double, 7, 7> I7 =
110 Eigen::Matrix<double, 7, 7>::Identity();
111 const Eigen::Matrix<double, 3, 3> I3 =
112 Eigen::Matrix<double, 3, 3>::Identity();
117 Eigen::Matrix<double, 7, 7> jacobi_i = Eigen::Matrix<double, 7, 7>::Zero();
118 jacobi_i.block<3, 3>(0, 0) = -
skew(phi);
119 jacobi_i.block<3, 3>(3, 3) = -(
skew(phi) + s * I3);
120 jacobi_i.block<3, 3>(3, 0) = -
skew(tau);
121 jacobi_i.block<3, 1>(3, 6) = tau;
124 Eigen::Matrix<double, 7, 7> adj_Sji = I7;
125 adj_Sji.block<3, 3>(0, 0) = Sji.
rotation().toRotationMatrix();
126 adj_Sji.block<3, 3>(3, 3) = Sji.
scale() * Sji.
rotation().toRotationMatrix();
127 adj_Sji.block<3, 3>(3, 0) =
134 Eigen::Matrix<double, 7, 7> jacobi_j = Eigen::Matrix<double, 7, 7>::Zero();
135 jacobi_j.block<3, 3>(0, 0) =
skew(phi);
136 jacobi_j.block<3, 3>(3, 3) =
skew(phi) + s * I3;
137 jacobi_j.block<3, 3>(3, 0) =
skew(tau);
138 jacobi_j.block<3, 1>(3, 6) = -tau;
BaseFixedSizedEdge< D, Sim3, VertexSim3Expmap, VertexSim3Expmap >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, Sim3, VertexSim3Expmap, VertexSim3Expmap >::template JacobianType< D, VertexXi::Dimension > & _jacobianOplusXi
bool writeInformationMatrix(std::ostream &os) const
write the upper trinagular part of the information matrix into the stream
bool readInformationMatrix(std::istream &is)
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
virtual void setMeasurement(const Measurement &m)
const ErrorVector & error() const
Measurement _measurement
the measurement of the edge
virtual void linearizeOplus()
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
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 EdgeInverseSim3ProjectXYZ()
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
7D edge between two Vertex7
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSim3()
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool write(std::ostream &os) const
write the vertex to a stream
VertexContainer _vertices
Vertex for a tracked point in space.
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (...
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool write(std::ostream &os) const
write the vertex to a stream
Vector2 _principle_point2
Vector2 _principle_point1
#define G2O_REGISTER_TYPE(name, classname)
#define G2O_REGISTER_TYPE_GROUP(typeGroupName)
#define G2O_USE_TYPE_GROUP(typeGroupName)
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
G2O_TYPES_SLAM3D_API Matrix3 skew(const Vector3 &v)
const Quaternion & rotation() const
const Vector3 & translation() const
const double & scale() const