11 os <<
"coeffs: " << v[0] <<
" " << v[1] <<
" " << v[2] <<
" " << v[3];
18 for (PlaneList::iterator it=l.begin(); it!=l.end(); it++){
25 for (PlaneList::const_iterator it=l.begin(); it!=l.end(); it++){
35 cerr <<
"p0 " << p << endl;
37 v << 0.5 , 0.2 , 0.1 , 10;
40 cerr <<
"p1 " << p1 << endl;
42 cerr <<
"p2 " << p2 << endl;
46 Vector3d mv = p2.
ominus(p1);
47 cerr <<
"p ominus p " << mv[0] <<
" " << mv[1] <<
" " << mv[2] << endl;
50 cerr <<
"p1 " << p1 << endl;
54 cerr <<
"p2 " << p2 << endl;
59 cerr <<
"p ominus p " << mv[0] <<
" " << mv[1] <<
" " << mv[2] << endl;
62 cerr <<
"p3 " << p3 << endl;
64 cerr <<
"p3.oplus(mv) " << p3 << endl;
68 Eigen::Vector4d coeffs;
69 coeffs << 1., 0., 0., 1.;
74 coeffs << 0., 1., 0., 1.;
79 coeffs << 0., 0., 1., 1.;
85 AngleAxisd r(AngleAxisd(0.0, Vector3d::UnitZ())
86 * AngleAxisd(0., Vector3d::UnitY())
87 * AngleAxisd(0., Vector3d::UnitX()));
89 SE3Quat t(r.toRotationMatrix(), Vector3d(0.9,0,0));
void oplus(const Eigen::Vector3d &v)
static double elevation(const Eigen::Vector3d &v)
Eigen::Vector3d ominus(const Plane3D &plane)
static double azimuth(const Eigen::Vector3d &v)
void transform(PlaneList &l, const SE3Quat &t)
void fromVector(const Eigen::Vector4d &coeffs_)
std::list< Plane3D * > PlaneList
std::ostream & operator<<(std::ostream &os, const G2OBatchStatistics &st)
Eigen::Vector3d normal() const
Eigen::Vector4d toVector() const