OOBB.hpp
Go to the documentation of this file.
1
2#pragma once
3
4#ifdef CGAL_FOUND
5
6#include <type_traits>
7
8#pragma GCC diagnostic push
9#pragma GCC diagnostic ignored "-Wpedantic"
10#include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
11#include <CGAL/convex_hull_2.h>
12#include <CGAL/min_quadrilateral_2.h>
13#pragma GCC diagnostic pop
14
15#include <pcl/point_cloud.h>
16#include <pcl/point_types.h>
17
18#include <SimoxUtility/shapes/OrientedBox.h>
19#include <SimoxUtility/shapes/XYConstrainedOrientedBox.h>
20
23
25
26namespace armarx
27{
28 template <class ST>
30 normalToRotation(const Eigen::Matrix<ST, 3, 1>& normal)
31 {
32 using VectorT = Eigen::Matrix<ST, 3, 1>;
33 using MatrixT = Eigen::Matrix<ST, 3, 3>;
34
35 MatrixT mx;
36 mx.col(0) = normal.normalized();
37 const VectorT other = (mx.col(0) == VectorT::UnitZ()) ? VectorT::UnitX() : VectorT::UnitZ();
38 mx.col(1) = mx.col(0).cross(other).normalized();
39 mx.col(2) = mx.col(0).cross(mx.col(1)).normalized();
40
41 return mx;
42 }
43
44 template <class T>
45 simox::OrientedBox<double>
46 calculate2dOOBB(const T& cloud, const Eigen::Vector3d& dir)
47 {
48 ARMARX_CHECK_GREATER(dir.norm(), 0.01) << VAROUT(dir.transpose());
49 const Eigen::Vector3d normal = dir.normalized();
50 using Kernel = CGAL::Exact_predicates_inexact_constructions_kernel;
51 using Point_2 = Kernel::Point_2;
52 using Polygon_2 = CGAL::Polygon_2<Kernel>;
53
54 const Eigen::Matrix3d boxFrame = normalToRotation(normal);
55 // const Eigen::Matrix3d boxFrame = Eigen::Matrix3d::Identity();
56
57 std::vector<Point_2> allProjected;
58 double allMaxX = -std::numeric_limits<double>::infinity();
59 double allMinX = +std::numeric_limits<double>::infinity();
60 {
61 const auto& consume = [&](auto x, auto y, auto z)
62 {
63 const Eigen::Vector3d t = boxFrame.transpose() * Eigen::Vector3d{x, y, z};
64 allProjected.emplace_back(t.y(), t.z());
65 allMinX = std::min(allMinX, t.x());
66 allMaxX = std::max(allMaxX, t.x());
67 };
68 const auto& resize = [&](auto size) { allProjected.reserve(size); };
69 VisitPointLikeContainer(cloud, resize, consume);
70 }
71 ARMARX_CHECK(!allProjected.empty());
72
73 std::vector<Point_2> chullAll;
74 CGAL::convex_hull_2(allProjected.begin(), allProjected.end(), std::back_inserter(chullAll));
75
76 Polygon_2 polyAll;
77 CGAL::min_rectangle_2(chullAll.begin(), chullAll.end(), std::back_inserter(polyAll));
78 const auto& polyps = polyAll.container();
79
80 ARMARX_CHECK_EQUAL(polyps.size(), 4) << '\n'
81 << VAROUT(normal.transpose()) << '\n'
82 << VAROUT(boxFrame) << '\n'
83 << VAROUT(allProjected.size()) << '\n'
84 << VAROUT(chullAll.size()) << '\n'
85 << VAROUT(polyAll.container().size());
86
87 const auto v0 = polyps.at(0) - polyps.at(1);
88 const auto v1 = polyps.at(2) - polyps.at(1);
89 return simox::OrientedBox<double>{
90 Eigen::Vector3d{allMinX, polyps.at(1).x(), polyps.at(1).y()}, //corner
91 Eigen::Vector3d{allMaxX - allMinX, 0, 0}, //v3 (in local frame it is x)
92 Eigen::Vector3d{0, v0.x(), v0.y()}, //v1
93 Eigen::Vector3d{0, v1.x(), v1.y()} //v2
94 }
95 .transformed(boxFrame);
96 }
97
98 template <class T>
99 simox::XYConstrainedOrientedBox<double>
100 calculateXYOOBB(const T& cloud)
101 {
102 const auto oobb = calculate2dOOBB(cloud, Eigen::Vector3d::UnitZ());
103 ARMARX_CHECK_GREATER(std::abs(oobb.axis_x().dot(Eigen::Vector3d::UnitZ())), 0.99)
104 << '\n'
105 << VAROUT(oobb.transformation()) << '\n'
106 << VAROUT(oobb.dimensions()) << '\n'
107 << VAROUT(oobb.axis_x().transpose());
108
109
110 const Eigen::Vector3d e1 = oobb.extend(1);
111 const Eigen::Vector3d e2 = oobb.extend(2);
112
113 return {oobb.translation(), {e1(0), e1(1)}, {e2(0), e2(1)}, oobb.dimension(0)};
114 }
115
116 template <class T>
117 simox::OrientedBox<double>
118 calculateDouble2dOOBB(const T& cloud)
119 {
120 const auto box1 = calculate2dOOBB(cloud, Eigen::Vector3d::UnitZ());
121
122 ARMARX_CHECK_GREATER(std::abs(box1.axis_x().normalized().dot(Eigen::Vector3d::UnitZ())),
123 0.99)
124 << '\n'
125 << VAROUT(box1.transformation());
126
127 const Eigen::Vector3d norm =
128 (box1.axis_y().norm() < box1.axis_z().norm()) ? box1.axis_y() : box1.axis_z();
129
130 const auto box2 = calculate2dOOBB(cloud, norm);
131 ARMARX_CHECK_GREATER(std::abs(box2.axis_x().normalized().dot(norm.normalized())), 0.99)
132 << '\n'
133 << VAROUT(box2.transformation()) << '\n'
134 << VAROUT(norm.transpose());
135
136 return box2;
137 }
138
139 template <class T>
140 inline std::vector<Eigen::Vector3f>
141 trimXYZHistogram(const T& cloud, const Eigen::Matrix3f& transform, const float trimEachSideBy)
142 {
143 std::vector<float> valuesX;
144 std::vector<float> valuesY;
145 std::vector<float> valuesZ;
146 std::size_t sz = 0;
147 {
148 const auto& consume = [&](auto x, auto y, auto z)
149 {
150 const Eigen::Vector3f ted = transform * Eigen::Vector3f{x, y, z};
151 valuesX.emplace_back(ted.x());
152 valuesY.emplace_back(ted.y());
153 valuesZ.emplace_back(ted.z());
154 };
155 const auto& resize = [&](auto size)
156 {
157 sz = size;
158 valuesX.reserve(size);
159 valuesY.reserve(size);
160 valuesZ.reserve(size);
161 };
162 VisitPointLikeContainer(cloud, resize, consume);
163 }
164
165 std::sort(valuesX.begin(), valuesX.end());
166 std::sort(valuesY.begin(), valuesY.end());
167 std::sort(valuesZ.begin(), valuesZ.end());
168
169 const std::size_t idxLo = sz * trimEachSideBy;
170 const std::size_t idxHi = sz - std::max(idxLo, 1ul);
171 const float loX = valuesX.at(idxLo);
172 const float hiX = valuesX.at(idxHi);
173 const float loY = valuesY.at(idxLo);
174 const float hiY = valuesY.at(idxHi);
175 const float loZ = valuesZ.at(idxLo);
176 const float hiZ = valuesZ.at(idxHi);
177
178
179 std::vector<Eigen::Vector3f> result;
180 {
181 const auto& consume = [&](auto x, auto y, auto z)
182 {
183 const Eigen::Vector3f ted = transform * Eigen::Vector3f{x, y, z};
184 if (ted.x() <= hiX && ted.x() >= loX && ted.y() <= hiY && ted.y() >= loY &&
185 ted.z() <= hiZ && ted.z() >= loZ)
186 {
187 result.emplace_back(x, y, z);
188 }
189 };
190 const auto& resize = [&](auto) {};
191 VisitPointLikeContainer(cloud, resize, consume);
192 }
193
194 return result;
195 }
196
197} // namespace armarx
198
199#endif
#define VAROUT(x)
#define ARMARX_CHECK_GREATER(lhs, rhs)
This macro evaluates whether lhs is greater (>) than rhs and if it turns out to be false it will thro...
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
This file offers overloads of toIce() and fromIce() functions for STL container types.
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition algorithm.h:351
void VisitPointLikeContainer(const auto &cloud, auto &&perElem, auto &&sizeInfo)
double norm(const Point &a)
Definition point.hpp:102