g2o
Loading...
Searching...
No Matches
line3d.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
3// All rights reserved.
4//
5// Redistribution and use in source and binary forms, with or without
6// modification, are permitted provided that the following conditions are
7// met:
8//
9// * Redistributions of source code must retain the above copyright notice,
10// this list of conditions and the following disclaimer.
11// * Redistributions in binary form must reproduce the above copyright
12// notice, this list of conditions and the following disclaimer in the
13// documentation and/or other materials provided with the distribution.
14//
15// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26
27#include "line3d.h"
28
29#include "g2o/stuff/misc.h"
30
31namespace g2o {
32
33using namespace std;
34
35static inline Matrix3 _skew(const Vector3& t) {
36 Matrix3 S;
37 S << 0, -t.z(), t.y(), t.z(), 0, -t.x(), -t.y(), t.x(), 0;
38 return S;
39}
40
42 Vector6 cartesian;
43 cartesian.tail<3>() = d() / d().norm();
44 Matrix3 W = -_skew(d());
45 double damping = cst(1e-9);
46 Matrix3 A = W.transpose() * W + (Matrix3::Identity() * damping);
47 cartesian.head<3>() = A.ldlt().solve(W.transpose() * w());
48 return cartesian;
49}
50
51Line3D operator*(const Isometry3& t, const Line3D& line) {
52 Matrix6 A = Matrix6::Zero();
53 A.block<3, 3>(0, 0) = t.linear();
54 A.block<3, 3>(0, 3) = _skew(t.translation()) * t.linear();
55 A.block<3, 3>(3, 3) = t.linear();
56 Vector6 v = (Vector6)line;
57 return Line3D(A * v);
58}
59
60namespace internal {
62 Vector6 l;
63 l.head<3>() = t * line.head<3>();
64 l.tail<3>() = t.linear() * line.tail<3>();
65 return normalizeCartesianLine(l);
66}
67
69 Vector3 p0 = line.head<3>();
70 Vector3 d0 = line.tail<3>();
71 d0.normalize();
72 p0 -= d0 * (d0.dot(p0));
73 Vector6 nl;
74 nl.head<3>() = p0;
75 nl.tail<3>() = d0;
76 return nl;
77}
78
79} // namespace internal
80
81} // namespace g2o
G2O_TYPES_SLAM3D_ADDONS_API Vector3 w() const
Definition line3d.h:68
G2O_TYPES_SLAM3D_ADDONS_API Vector3 d() const
Definition line3d.h:70
G2O_TYPES_SLAM3D_ADDONS_API Vector6 toCartesian() const
Definition line3d.cpp:41
some general case utility functions
Vector6 transformCartesianLine(const Isometry3 &t, const Vector6 &line)
Definition line3d.cpp:61
Vector6 normalizeCartesianLine(const Vector6 &line)
Definition line3d.cpp:68
VectorN< 3 > Vector3
Definition eigen_types.h:51
Eigen::Matrix< double, 6, 6 > Matrix6
Definition line3d.h:38
static Matrix3 _skew(const Vector3 &t)
Definition line3d.cpp:35
MatrixN< 3 > Matrix3
Definition eigen_types.h:72
Line2D operator*(const SE2 &t, const Line2D &l)
Definition line_2d.h:47
constexpr double cst(long double v)
Definition misc.h:60
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77
VectorN< 6 > Vector6
Definition eigen_types.h:53
Definition jet.h:876