-
Notifications
You must be signed in to change notification settings - Fork 92
/
bodies.cpp
1316 lines (1139 loc) · 37.2 KB
/
bodies.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Ioan Sucan */
#include "geometric_shapes/bodies.h"
#include "geometric_shapes/body_operations.h"
#include <console_bridge/console.h>
extern "C" {
#ifdef GEOMETRIC_SHAPES_HAVE_QHULL_2011
#include <libqhull/libqhull.h>
#include <libqhull/mem.h>
#include <libqhull/qset.h>
#include <libqhull/geom.h>
#include <libqhull/merge.h>
#include <libqhull/poly.h>
#include <libqhull/io.h>
#include <libqhull/stat.h>
#else
#include <qhull/qhull.h>
#include <qhull/mem.h>
#include <qhull/qset.h>
#include <qhull/geom.h>
#include <qhull/merge.h>
#include <qhull/poly.h>
#include <qhull/io.h>
#include <qhull/stat.h>
#endif
}
#include <boost/math/constants/constants.hpp>
#include <limits>
#include <cstdio>
#include <algorithm>
#include <Eigen/Geometry>
namespace bodies
{
namespace detail
{
static const double ZERO = 1e-9;
/** \brief Compute the square of the distance between a ray and a point
Note: this requires 'dir' to be normalized */
static inline double distanceSQR(const Eigen::Vector3d& p, const Eigen::Vector3d& origin, const Eigen::Vector3d& dir)
{
Eigen::Vector3d a = p - origin;
double d = dir.normalized().dot(a);
return a.squaredNorm() - d * d;
}
// temp structure for intersection points (used for ordering them)
struct intersc
{
intersc(const Eigen::Vector3d& _pt, const double _tm) : pt(_pt), time(_tm)
{
}
Eigen::Vector3d pt;
double time;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
// define order on intersection points
struct interscOrder
{
bool operator()(const intersc& a, const intersc& b) const
{
return a.time < b.time;
}
};
} // namespace detail
} // namespace bodies
void bodies::Body::setDimensions(const shapes::Shape* shape)
{
useDimensions(shape);
updateInternalData();
}
bool bodies::Body::samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int max_attempts,
Eigen::Vector3d& result)
{
BoundingSphere bs;
computeBoundingSphere(bs);
for (unsigned int i = 0; i < max_attempts; ++i)
{
result = Eigen::Vector3d(rng.uniformReal(bs.center.x() - bs.radius, bs.center.x() + bs.radius),
rng.uniformReal(bs.center.y() - bs.radius, bs.center.y() + bs.radius),
rng.uniformReal(bs.center.z() - bs.radius, bs.center.z() + bs.radius));
if (containsPoint(result))
return true;
}
return false;
}
bool bodies::Sphere::containsPoint(const Eigen::Vector3d& p, bool /* verbose */) const
{
return (center_ - p).squaredNorm() <= radius2_;
}
void bodies::Sphere::useDimensions(const shapes::Shape* shape) // radius
{
radius_ = static_cast<const shapes::Sphere*>(shape)->radius;
}
std::vector<double> bodies::Sphere::getDimensions() const
{
std::vector<double> d(1, radius_);
return d;
}
void bodies::Sphere::updateInternalData()
{
const auto tmpRadiusU = radius_ * scale_ + padding_;
if (tmpRadiusU < 0)
throw std::runtime_error("Sphere radius must be non-negative.");
radiusU_ = tmpRadiusU;
radius2_ = radiusU_ * radiusU_;
center_ = pose_.translation();
}
std::shared_ptr<bodies::Body> bodies::Sphere::cloneAt(const Eigen::Isometry3d& pose, double padding, double scale) const
{
auto s = std::make_shared<Sphere>();
s->radius_ = radius_;
s->padding_ = padding;
s->scale_ = scale;
s->pose_ = pose;
s->updateInternalData();
return s;
}
double bodies::Sphere::computeVolume() const
{
return 4.0 * boost::math::constants::pi<double>() * radiusU_ * radiusU_ * radiusU_ / 3.0;
}
void bodies::Sphere::computeBoundingSphere(BoundingSphere& sphere) const
{
sphere.center = center_;
sphere.radius = radiusU_;
}
void bodies::Sphere::computeBoundingCylinder(BoundingCylinder& cylinder) const
{
cylinder.pose = pose_;
cylinder.radius = radiusU_;
cylinder.length = radiusU_;
}
void bodies::Sphere::computeBoundingBox(bodies::AABB& bbox) const
{
bbox.setEmpty();
// it's a sphere, so we do not rotate the bounding box
Eigen::Isometry3d transform = Eigen::Isometry3d::Identity();
transform.translation() = getPose().translation();
bbox.extendWithTransformedBox(transform, Eigen::Vector3d(2 * radiusU_, 2 * radiusU_, 2 * radiusU_));
}
bool bodies::Sphere::samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int max_attempts,
Eigen::Vector3d& result)
{
for (unsigned int i = 0; i < max_attempts; ++i)
{
const double minX = center_.x() - radiusU_;
const double maxX = center_.x() + radiusU_;
const double minY = center_.y() - radiusU_;
const double maxY = center_.y() + radiusU_;
const double minZ = center_.z() - radiusU_;
const double maxZ = center_.z() + radiusU_;
// we are sampling in a box; the probability of success after 20 attempts is 99.99996% given the ratio of box volume
// to sphere volume
for (int j = 0; j < 20; ++j)
{
result = Eigen::Vector3d(rng.uniformReal(minX, maxX), rng.uniformReal(minY, maxY), rng.uniformReal(minZ, maxZ));
if (containsPoint(result))
return true;
}
}
return false;
}
bool bodies::Sphere::intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections, unsigned int count) const
{
if (detail::distanceSQR(center_, origin, dir) > radius2_)
return false;
bool result = false;
Eigen::Vector3d cp = origin - center_;
double dpcpv = cp.dot(dir);
Eigen::Vector3d w = cp - dpcpv * dir;
Eigen::Vector3d Q = center_ + w;
double x = radius2_ - w.squaredNorm();
if (fabs(x) < detail::ZERO)
{
w = Q - origin;
double dpQv = w.dot(dir);
if (dpQv > detail::ZERO)
{
if (intersections)
intersections->push_back(Q);
result = true;
}
}
else if (x > 0.0)
{
x = sqrt(x);
w = dir * x;
Eigen::Vector3d A = Q - w;
Eigen::Vector3d B = Q + w;
w = A - origin;
double dpAv = w.dot(dir);
w = B - origin;
double dpBv = w.dot(dir);
if (dpAv > detail::ZERO)
{
result = true;
if (intersections)
{
intersections->push_back(A);
if (count == 1)
return result;
}
}
if (dpBv > detail::ZERO)
{
result = true;
if (intersections)
intersections->push_back(B);
}
}
return result;
}
bool bodies::Cylinder::containsPoint(const Eigen::Vector3d& p, bool /* verbose */) const
{
Eigen::Vector3d v = p - center_;
double pH = v.dot(normalH_);
if (fabs(pH) > length2_)
return false;
double pB1 = v.dot(normalB1_);
double remaining = radius2_ - pB1 * pB1;
if (remaining < 0.0)
return false;
else
{
double pB2 = v.dot(normalB2_);
return pB2 * pB2 <= remaining;
}
}
void bodies::Cylinder::useDimensions(const shapes::Shape* shape) // (length, radius)
{
length_ = static_cast<const shapes::Cylinder*>(shape)->length;
radius_ = static_cast<const shapes::Cylinder*>(shape)->radius;
}
std::vector<double> bodies::Cylinder::getDimensions() const
{
std::vector<double> d(2);
d[0] = radius_;
d[1] = length_;
return d;
}
void bodies::Cylinder::updateInternalData()
{
const auto tmpRadiusU = radius_ * scale_ + padding_;
if (tmpRadiusU < 0)
throw std::runtime_error("Cylinder radius must be non-negative.");
const auto tmpLength2 = scale_ * length_ / 2.0 + padding_;
if (tmpLength2 < 0)
throw std::runtime_error("Cylinder length must be non-negative.");
radiusU_ = tmpRadiusU;
length2_ = tmpLength2;
radius2_ = radiusU_ * radiusU_;
center_ = pose_.translation();
radiusBSqr_ = length2_ * length2_ + radius2_;
radiusB_ = sqrt(radiusBSqr_);
Eigen::Matrix3d basis = pose_.rotation();
normalB1_ = basis.col(0);
normalB2_ = basis.col(1);
normalH_ = basis.col(2);
double tmp = -normalH_.dot(center_);
d1_ = tmp + length2_;
d2_ = tmp - length2_;
}
bool bodies::Cylinder::samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int /* max_attempts */,
Eigen::Vector3d& result)
{
// sample a point on the base disc of the cylinder
double a = rng.uniformReal(-boost::math::constants::pi<double>(), boost::math::constants::pi<double>());
double r = rng.uniformReal(-radiusU_, radiusU_);
double x = cos(a) * r;
double y = sin(a) * r;
// sample e height
double z = rng.uniformReal(-length2_, length2_);
result = Eigen::Vector3d(x, y, z);
return true;
}
std::shared_ptr<bodies::Body> bodies::Cylinder::cloneAt(const Eigen::Isometry3d& pose, double padding,
double scale) const
{
auto c = std::make_shared<Cylinder>();
c->length_ = length_;
c->radius_ = radius_;
c->padding_ = padding;
c->scale_ = scale;
c->pose_ = pose;
c->updateInternalData();
return c;
}
double bodies::Cylinder::computeVolume() const
{
return 2.0 * boost::math::constants::pi<double>() * radius2_ * length2_;
}
void bodies::Cylinder::computeBoundingSphere(BoundingSphere& sphere) const
{
sphere.center = center_;
sphere.radius = radiusB_;
}
void bodies::Cylinder::computeBoundingCylinder(BoundingCylinder& cylinder) const
{
cylinder.pose = pose_;
cylinder.radius = radiusU_;
cylinder.length = scale_ * length_ + padding_;
}
void bodies::Cylinder::computeBoundingBox(bodies::AABB& bbox) const
{
bbox.setEmpty();
// method taken from http://www.iquilezles.org/www/articles/diskbbox/diskbbox.htm
const auto a = normalH_;
const auto e = radiusU_ * (Eigen::Vector3d::Ones() - a.cwiseProduct(a) / a.dot(a)).cwiseSqrt();
const auto pa = center_ + length2_ * normalH_;
const auto pb = center_ - length2_ * normalH_;
bbox.extend(pa - e);
bbox.extend(pa + e);
bbox.extend(pb - e);
bbox.extend(pb + e);
}
bool bodies::Cylinder::intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections, unsigned int count) const
{
if (detail::distanceSQR(center_, origin, dir) > radiusBSqr_)
return false;
std::vector<detail::intersc> ipts;
// intersect bases
double tmp = normalH_.dot(dir);
if (fabs(tmp) > detail::ZERO)
{
double tmp2 = -normalH_.dot(origin);
double t1 = (tmp2 - d1_) / tmp;
if (t1 > 0.0)
{
Eigen::Vector3d p1(origin + dir * t1);
Eigen::Vector3d v1(p1 - center_);
v1 = v1 - normalH_.dot(v1) * normalH_;
if (v1.squaredNorm() < radius2_ + detail::ZERO)
{
if (intersections == nullptr)
return true;
detail::intersc ip(p1, t1);
ipts.push_back(ip);
}
}
double t2 = (tmp2 - d2_) / tmp;
if (t2 > 0.0)
{
Eigen::Vector3d p2(origin + dir * t2);
Eigen::Vector3d v2(p2 - center_);
v2 = v2 - normalH_.dot(v2) * normalH_;
if (v2.squaredNorm() < radius2_ + detail::ZERO)
{
if (intersections == nullptr)
return true;
detail::intersc ip(p2, t2);
ipts.push_back(ip);
}
}
}
if (ipts.size() < 2)
{
// intersect with infinite cylinder
Eigen::Vector3d VD(normalH_.cross(dir));
Eigen::Vector3d ROD(normalH_.cross(origin - center_));
double a = VD.squaredNorm();
double b = 2.0 * ROD.dot(VD);
double c = ROD.squaredNorm() - radius2_;
double d = b * b - 4.0 * a * c;
if (d > 0.0 && fabs(a) > detail::ZERO)
{
d = sqrt(d);
double e = -a * 2.0;
double t1 = (b + d) / e;
double t2 = (b - d) / e;
if (t1 > 0.0)
{
Eigen::Vector3d p1(origin + dir * t1);
Eigen::Vector3d v1(center_ - p1);
if (fabs(normalH_.dot(v1)) < length2_ + detail::ZERO)
{
if (intersections == nullptr)
return true;
detail::intersc ip(p1, t1);
ipts.push_back(ip);
}
}
if (t2 > 0.0)
{
Eigen::Vector3d p2(origin + dir * t2);
Eigen::Vector3d v2(center_ - p2);
if (fabs(normalH_.dot(v2)) < length2_ + detail::ZERO)
{
if (intersections == nullptr)
return true;
detail::intersc ip(p2, t2);
ipts.push_back(ip);
}
}
}
}
if (ipts.empty())
return false;
std::sort(ipts.begin(), ipts.end(), detail::interscOrder());
const unsigned int n = count > 0 ? std::min<unsigned int>(count, ipts.size()) : ipts.size();
for (unsigned int i = 0; i < n; ++i)
intersections->push_back(ipts[i].pt);
return true;
}
bool bodies::Box::samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int /* max_attempts */,
Eigen::Vector3d& result)
{
result = pose_ * Eigen::Vector3d(rng.uniformReal(-length2_, length2_), rng.uniformReal(-width2_, width2_),
rng.uniformReal(-height2_, height2_));
return true;
}
bool bodies::Box::containsPoint(const Eigen::Vector3d& p, bool /* verbose */) const
{
Eigen::Vector3d v = p - center_;
double pL = v.dot(normalL_);
if (fabs(pL) > length2_)
return false;
double pW = v.dot(normalW_);
if (fabs(pW) > width2_)
return false;
double pH = v.dot(normalH_);
return fabs(pH) <= height2_;
}
void bodies::Box::useDimensions(const shapes::Shape* shape) // (x, y, z) = (length, width, height)
{
const double* size = static_cast<const shapes::Box*>(shape)->size;
length_ = size[0];
width_ = size[1];
height_ = size[2];
}
std::vector<double> bodies::Box::getDimensions() const
{
std::vector<double> d(3);
d[0] = length_;
d[1] = width_;
d[2] = height_;
return d;
}
void bodies::Box::updateInternalData()
{
double s2 = scale_ / 2.0;
const auto tmpLength2 = length_ * s2 + padding_;
const auto tmpWidth2 = width_ * s2 + padding_;
const auto tmpHeight2 = height_ * s2 + padding_;
if (tmpLength2 < 0 || tmpWidth2 < 0 || tmpHeight2 < 0)
throw std::runtime_error("Box dimensions must be non-negative.");
length2_ = tmpLength2;
width2_ = tmpWidth2;
height2_ = tmpHeight2;
center_ = pose_.translation();
radius2_ = length2_ * length2_ + width2_ * width2_ + height2_ * height2_;
radiusB_ = sqrt(radius2_);
Eigen::Matrix3d basis = pose_.rotation();
normalL_ = basis.col(0);
normalW_ = basis.col(1);
normalH_ = basis.col(2);
const Eigen::Vector3d tmp(normalL_ * length2_ + normalW_ * width2_ + normalH_ * height2_);
corner1_ = center_ - tmp;
corner2_ = center_ + tmp;
}
std::shared_ptr<bodies::Body> bodies::Box::cloneAt(const Eigen::Isometry3d& pose, double padding, double scale) const
{
auto b = std::make_shared<Box>();
b->length_ = length_;
b->width_ = width_;
b->height_ = height_;
b->padding_ = padding;
b->scale_ = scale;
b->pose_ = pose;
b->updateInternalData();
return b;
}
double bodies::Box::computeVolume() const
{
return 8.0 * length2_ * width2_ * height2_;
}
void bodies::Box::computeBoundingSphere(BoundingSphere& sphere) const
{
sphere.center = center_;
sphere.radius = radiusB_;
}
void bodies::Box::computeBoundingCylinder(BoundingCylinder& cylinder) const
{
double a, b;
if (length2_ > width2_ && length2_ > height2_)
{
cylinder.length = length2_ * 2.0;
a = width2_;
b = height2_;
Eigen::Isometry3d rot(Eigen::AngleAxisd(90.0f * (M_PI / 180.0f), Eigen::Vector3d::UnitY()));
cylinder.pose = pose_ * rot;
}
else if (width2_ > height2_)
{
cylinder.length = width2_ * 2.0;
a = height2_;
b = length2_;
cylinder.radius = sqrt(height2_ * height2_ + length2_ * length2_);
Eigen::Isometry3d rot(Eigen::AngleAxisd(90.0f * (M_PI / 180.0f), Eigen::Vector3d::UnitX()));
cylinder.pose = pose_ * rot;
}
else
{
cylinder.length = height2_ * 2.0;
a = width2_;
b = length2_;
cylinder.pose = pose_;
}
cylinder.radius = sqrt(a * a + b * b);
}
void bodies::Box::computeBoundingBox(bodies::AABB& bbox) const
{
bbox.setEmpty();
bbox.extendWithTransformedBox(getPose(), 2 * Eigen::Vector3d(length2_, width2_, height2_));
}
bool bodies::Box::intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
EigenSTL::vector_Vector3d* intersections, unsigned int count) const
{
// Brian Smits. Efficient bounding box intersection. Ray tracing news 15(1), 2002
float tmin, tmax, tymin, tymax, tzmin, tzmax;
float divx, divy, divz;
divx = 1 / dir.x();
if (divx >= 0)
{
tmin = (corner1_.x() - origin.x()) * divx;
tmax = (corner2_.x() - origin.x()) * divx;
}
else
{
tmax = (corner1_.x() - origin.x()) * divx;
tmin = (corner2_.x() - origin.x()) * divx;
}
divy = 1 / dir.y();
if (dir.y() >= 0)
{
tymin = (corner1_.y() - origin.y()) * divy;
tymax = (corner2_.y() - origin.y()) * divy;
}
else
{
tymax = (corner1_.y() - origin.y()) * divy;
tymin = (corner2_.y() - origin.y()) * divy;
}
if ((tmin > tymax || tymin > tmax))
return false;
if (tymin > tmin)
tmin = tymin;
if (tymax < tmax)
tmax = tymax;
divz = 1 / dir.z();
if (dir.z() >= 0)
{
tzmin = (corner1_.z() - origin.z()) * divz;
tzmax = (corner2_.z() - origin.z()) * divz;
}
else
{
tzmax = (corner1_.z() - origin.z()) * divz;
tzmin = (corner2_.z() - origin.z()) * divz;
}
if ((tmin > tzmax || tzmin > tmax))
return false;
if (tzmin > tmin)
tmin = tzmin;
if (tzmax < tmax)
tmax = tzmax;
if (tmax < 0)
return false;
if (intersections)
{
if (tmax - tmin > detail::ZERO)
{
intersections->push_back(tmin * dir + origin);
if (count > 1)
intersections->push_back(tmax * dir + origin);
}
else
intersections->push_back(tmax * dir + origin);
}
return true;
}
bool bodies::ConvexMesh::containsPoint(const Eigen::Vector3d& p, bool /* verbose */) const
{
if (!mesh_data_)
return false;
if (bounding_box_.containsPoint(p))
{
Eigen::Vector3d ip(i_pose_ * p);
ip = mesh_data_->mesh_center_ + (ip - mesh_data_->mesh_center_) / scale_;
return isPointInsidePlanes(ip);
}
else
return false;
}
void bodies::ConvexMesh::correctVertexOrderFromPlanes()
{
for (unsigned int i = 0; i < mesh_data_->triangles_.size(); i += 3)
{
Eigen::Vector3d d1 =
mesh_data_->vertices_[mesh_data_->triangles_[i]] - mesh_data_->vertices_[mesh_data_->triangles_[i + 1]];
Eigen::Vector3d d2 =
mesh_data_->vertices_[mesh_data_->triangles_[i]] - mesh_data_->vertices_[mesh_data_->triangles_[i + 2]];
// expected computed normal from triangle vertex order
Eigen::Vector3d tri_normal = d1.cross(d2);
tri_normal.normalize();
// actual plane normal
Eigen::Vector3d normal(mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].x(),
mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].y(),
mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].z());
bool same_dir = tri_normal.dot(normal) > 0;
if (!same_dir)
{
std::swap(mesh_data_->triangles_[i], mesh_data_->triangles_[i + 1]);
}
}
}
void bodies::ConvexMesh::useDimensions(const shapes::Shape* shape)
{
mesh_data_ = std::make_shared<MeshData>();
const shapes::Mesh* mesh = static_cast<const shapes::Mesh*>(shape);
double maxX = -std::numeric_limits<double>::infinity(), maxY = -std::numeric_limits<double>::infinity(),
maxZ = -std::numeric_limits<double>::infinity();
double minX = std::numeric_limits<double>::infinity(), minY = std::numeric_limits<double>::infinity(),
minZ = std::numeric_limits<double>::infinity();
for (unsigned int i = 0; i < mesh->vertex_count; ++i)
{
double vx = mesh->vertices[3 * i];
double vy = mesh->vertices[3 * i + 1];
double vz = mesh->vertices[3 * i + 2];
if (maxX < vx)
maxX = vx;
if (maxY < vy)
maxY = vy;
if (maxZ < vz)
maxZ = vz;
if (minX > vx)
minX = vx;
if (minY > vy)
minY = vy;
if (minZ > vz)
minZ = vz;
}
if (maxX < minX)
maxX = minX = 0.0;
if (maxY < minY)
maxY = minY = 0.0;
if (maxZ < minZ)
maxZ = minZ = 0.0;
mesh_data_->box_size_ = Eigen::Vector3d(maxX - minX, maxY - minY, maxZ - minZ);
mesh_data_->box_offset_ = Eigen::Vector3d((minX + maxX) / 2.0, (minY + maxY) / 2.0, (minZ + maxZ) / 2.0);
mesh_data_->planes_.clear();
mesh_data_->triangles_.clear();
mesh_data_->vertices_.clear();
mesh_data_->mesh_radiusB_ = 0.0;
mesh_data_->mesh_center_ = Eigen::Vector3d();
double xdim = maxX - minX;
double ydim = maxY - minY;
double zdim = maxZ - minZ;
double pose1;
double pose2;
unsigned int off1;
unsigned int off2;
/* compute bounding cylinder */
double cyl_length;
double maxdist = -std::numeric_limits<double>::infinity();
if (xdim > ydim && xdim > zdim)
{
off1 = 1;
off2 = 2;
pose1 = mesh_data_->box_offset_.y();
pose2 = mesh_data_->box_offset_.z();
cyl_length = xdim;
}
else if (ydim > zdim)
{
off1 = 0;
off2 = 2;
pose1 = mesh_data_->box_offset_.x();
pose2 = mesh_data_->box_offset_.z();
cyl_length = ydim;
}
else
{
off1 = 0;
off2 = 1;
pose1 = mesh_data_->box_offset_.x();
pose2 = mesh_data_->box_offset_.y();
cyl_length = zdim;
}
/* compute convex hull */
coordT* points = (coordT*)calloc(mesh->vertex_count * 3, sizeof(coordT));
for (unsigned int i = 0; i < mesh->vertex_count; ++i)
{
points[3 * i + 0] = (coordT)mesh->vertices[3 * i + 0];
points[3 * i + 1] = (coordT)mesh->vertices[3 * i + 1];
points[3 * i + 2] = (coordT)mesh->vertices[3 * i + 2];
double dista = mesh->vertices[3 * i + off1] - pose1;
double distb = mesh->vertices[3 * i + off2] - pose2;
double dist = sqrt(((dista * dista) + (distb * distb)));
if (dist > maxdist)
maxdist = dist;
}
mesh_data_->bounding_cylinder_.radius = maxdist;
mesh_data_->bounding_cylinder_.length = cyl_length;
static FILE* null = fopen("/dev/null", "w");
char flags[] = "qhull Tv Qt";
int exitcode = qh_new_qhull(3, mesh->vertex_count, points, true, flags, null, null);
if (exitcode != 0)
{
CONSOLE_BRIDGE_logWarn("Convex hull creation failed");
qh_freeqhull(!qh_ALL);
int curlong, totlong;
qh_memfreeshort(&curlong, &totlong);
return;
}
int num_facets = qh num_facets;
int num_vertices = qh num_vertices;
mesh_data_->vertices_.reserve(num_vertices);
Eigen::Vector3d sum(0, 0, 0);
// necessary for FORALLvertices
std::map<unsigned int, unsigned int> qhull_vertex_table;
vertexT* vertex;
FORALLvertices
{
Eigen::Vector3d vert(vertex->point[0], vertex->point[1], vertex->point[2]);
qhull_vertex_table[vertex->id] = mesh_data_->vertices_.size();
sum += vert;
mesh_data_->vertices_.push_back(vert);
}
mesh_data_->mesh_center_ = sum / (double)(num_vertices);
for (unsigned int j = 0; j < mesh_data_->vertices_.size(); ++j)
{
double dist = (mesh_data_->vertices_[j] - mesh_data_->mesh_center_).squaredNorm();
if (dist > mesh_data_->mesh_radiusB_)
mesh_data_->mesh_radiusB_ = dist;
}
mesh_data_->mesh_radiusB_ = sqrt(mesh_data_->mesh_radiusB_);
mesh_data_->triangles_.reserve(num_facets);
// neccessary for qhull macro
facetT* facet;
FORALLfacets
{
Eigen::Vector4d planeEquation(facet->normal[0], facet->normal[1], facet->normal[2], facet->offset);
if (!mesh_data_->planes_.empty())
{
// filter equal planes - assuming same ones follow each other
if ((planeEquation - mesh_data_->planes_.back()).cwiseAbs().maxCoeff() > 1e-6) // max diff to last
mesh_data_->planes_.push_back(planeEquation);
}
else
{
mesh_data_->planes_.push_back(planeEquation);
}
// Needed by FOREACHvertex_i_
int vertex_n, vertex_i;
FOREACHvertex_i_((*facet).vertices)
{
mesh_data_->triangles_.push_back(qhull_vertex_table[vertex->id]);
}
mesh_data_->plane_for_triangle_[(mesh_data_->triangles_.size() - 1) / 3] = mesh_data_->planes_.size() - 1;
}
qh_freeqhull(!qh_ALL);
int curlong, totlong;
qh_memfreeshort(&curlong, &totlong);
}
std::vector<double> bodies::ConvexMesh::getDimensions() const
{
return std::vector<double>();
}
void bodies::ConvexMesh::computeScaledVerticesFromPlaneProjections()
{
// compute the scaled vertices, if needed
if (padding_ == 0.0 && scale_ == 1.0)
{
scaled_vertices_ = &mesh_data_->vertices_;
return;
}
if (!scaled_vertices_storage_)
scaled_vertices_storage_.reset(new EigenSTL::vector_Vector3d());
scaled_vertices_ = scaled_vertices_storage_.get();
scaled_vertices_storage_->resize(mesh_data_->vertices_.size());
// project vertices along the vertex - center line to the scaled and padded plane
// take the average of all tri's planes around that vertex as the result
// is not unique
// First figure out, which tris are connected to each vertex
std::map<unsigned int, std::vector<unsigned int> > vertex_to_tris;
for (unsigned int i = 0; i < mesh_data_->triangles_.size() / 3; ++i)
{
vertex_to_tris[mesh_data_->triangles_[3 * i + 0]].push_back(i);
vertex_to_tris[mesh_data_->triangles_[3 * i + 1]].push_back(i);
vertex_to_tris[mesh_data_->triangles_[3 * i + 2]].push_back(i);
}
for (unsigned int i = 0; i < mesh_data_->vertices_.size(); ++i)
{
Eigen::Vector3d v(mesh_data_->vertices_[i] - mesh_data_->mesh_center_);
EigenSTL::vector_Vector3d projected_vertices;
for (unsigned int t : vertex_to_tris[i])
{
const Eigen::Vector4d& plane = mesh_data_->planes_[mesh_data_->plane_for_triangle_[t]];
Eigen::Vector3d plane_normal(plane.x(), plane.y(), plane.z());
double d_scaled_padded =
scale_ * plane.w() - (1 - scale_) * mesh_data_->mesh_center_.dot(plane_normal) - padding_;
// intersect vert - center with scaled/padded plane equation
double denom = v.dot(plane_normal);
if (fabs(denom) < 1e-3)
continue;
double lambda = (-mesh_data_->mesh_center_.dot(plane_normal) - d_scaled_padded) / denom;
Eigen::Vector3d vert_on_plane = v * lambda + mesh_data_->mesh_center_;
projected_vertices.push_back(vert_on_plane);
}
if (projected_vertices.empty())
{
double l = v.norm();
scaled_vertices_storage_->at(i) =
mesh_data_->mesh_center_ + v * (scale_ + (l > detail::ZERO ? padding_ / l : 0.0));
}
else
{
Eigen::Vector3d sum(0, 0, 0);
for (const Eigen::Vector3d& vertex : projected_vertices)
{
sum += vertex;
}
sum /= projected_vertices.size();
scaled_vertices_storage_->at(i) = sum;
}
}
}
void bodies::ConvexMesh::updateInternalData()
{
if (!mesh_data_)
return;
Eigen::Isometry3d pose = pose_;
pose.translation() = Eigen::Vector3d(pose_ * mesh_data_->box_offset_);