capsule_box_2.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014-2015, CNRS-LAAS and AIST
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of CNRS-LAAS and AIST nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #define BOOST_TEST_MODULE COAL_GEOMETRIC_SHAPES
38 #include <boost/test/included/unit_test.hpp>
39 
40 #define CHECK_CLOSE_TO_0(x, eps) BOOST_CHECK_CLOSE((x + 1.0), (1.0), (eps))
41 
42 #include "utility.h"
43 
44 #include <cmath>
45 #include "coal/distance.h"
46 #include "coal/math/transform.h"
47 #include "coal/collision.h"
48 #include "coal/collision_object.h"
50 
51 BOOST_AUTO_TEST_CASE(distance_capsule_box) {
52  typedef coal::shared_ptr<coal::CollisionGeometry> CollisionGeometryPtr_t;
53  // Capsule of radius 2 and of height 4
54  CollisionGeometryPtr_t capsuleGeometry(new coal::Capsule(2., 4.));
55  // Box of size 1 by 2 by 4
56  CollisionGeometryPtr_t boxGeometry(new coal::Box(1., 2., 4.));
57 
58  // Enable computation of nearest points
59  coal::DistanceRequest distanceRequest(true, 0, 0);
60  coal::DistanceResult distanceResult;
61 
62  // Rotate capsule around y axis by pi/2 and move it behind box
63  coal::Transform3s tf1(coal::makeQuat(sqrt(2) / 2, 0, sqrt(2) / 2, 0),
64  coal::Vec3s(-10., 0.8, 1.5));
66  coal::CollisionObject capsule(capsuleGeometry, tf1);
67  coal::CollisionObject box(boxGeometry, tf2);
68 
69  // test distance
70  distanceResult.clear();
71  coal::distance(&capsule, &box, distanceRequest, distanceResult);
72  coal::Vec3s o1 = distanceResult.nearest_points[0];
73  coal::Vec3s o2 = distanceResult.nearest_points[1];
74 
75  BOOST_CHECK_CLOSE(distanceResult.min_distance, 5.5, 1e-2);
76  BOOST_CHECK_CLOSE(o1[0], -6, 1e-2);
77  BOOST_CHECK_CLOSE(o1[1], 0.8, 1e-1);
78  BOOST_CHECK_CLOSE(o1[2], 1.5, 1e-2);
79  BOOST_CHECK_CLOSE(o2[0], -0.5, 1e-2);
80  BOOST_CHECK_CLOSE(o2[1], 0.8, 1e-1);
81  BOOST_CHECK_CLOSE(o2[2], 1.5, 1e-2);
82 }
collision.h
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
collision_manager.box
box
Definition: collision_manager.py:11
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
coal::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: coal/shape/geometric_shapes.h:383
utility.h
coal::distance
COAL_DLLAPI CoalScalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:180
collision_object.h
coal::Box
Center at zero point, axis aligned box.
Definition: coal/shape/geometric_shapes.h:166
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::DistanceResult::min_distance
CoalScalar min_distance
minimum distance between two objects. If two objects are in collision and DistanceRequest::enable_sig...
Definition: coal/collision_data.h:1058
transform.h
coal::DistanceRequest
request to the distance computation
Definition: coal/collision_data.h:985
distance.h
coal::DistanceResult
distance result
Definition: coal/collision_data.h:1051
coal::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: coal/collision_object.h:214
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(distance_capsule_box)
Definition: capsule_box_2.cpp:51
coal::makeQuat
Quatf makeQuat(CoalScalar w, CoalScalar x, CoalScalar y, CoalScalar z)
Definition: utility.cpp:370
geometric_shapes.h
coal::DistanceResult::clear
void clear()
clear the result
Definition: coal/collision_data.h:1139
coal::DistanceResult::nearest_points
std::array< Vec3s, 2 > nearest_points
nearest points. See CollisionResult::nearest_points.
Definition: coal/collision_data.h:1065
coal::CollisionGeometryPtr_t
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
Definition: include/coal/fwd.hh:134


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57