test_fcl_general.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #include <iostream>
39 
40 #include "fcl/fcl.h"
41 
42 #include "gtest/gtest.h"
43 
44 using namespace std;
45 using namespace fcl;
46 
47 //==============================================================================
48 template <typename S>
50 {
51  std::shared_ptr<Box<S>> box0(new Box<S>(1,1,1));
52  std::shared_ptr<Box<S>> box1(new Box<S>(1,1,1));
53 
54 // GJKSolver_indep solver;
56  std::vector<ContactPoint<S>> contact_points;
57 
58  Transform3<S> tf0, tf1;
59  tf0.setIdentity();
60  tf0.translation() = Vector3<S>(.9,0,0);
61  tf0.linear() = Quaternion<S>(.6, .8, 0, 0).toRotationMatrix();
62  tf1.setIdentity();
63 
64  bool res = solver.shapeIntersect(*box0, tf0, *box1, tf1, &contact_points);
65 
66  EXPECT_TRUE(true);
67 
68  for (const auto& contact_point : contact_points)
69  {
70  cout << "contact points: " << contact_point.pos.transpose() << endl;
71  cout << "pen depth: " << contact_point.penetration_depth << endl;
72  cout << "normal: " << contact_point.normal << endl;
73  }
74  cout << "result: " << res << endl;
75 
77  static const bool enable_contact = true;
81 
82  CollisionObject<S> co0(box0, tf0);
83  CollisionObject<S> co1(box1, tf1);
84 
85  fcl::collide(&co0, &co1, request, result);
86  vector<Contact<S>> contacts;
87  result.getContacts(contacts);
88 
89  cout << contacts.size() << " contacts found" << endl;
90  for(const Contact<S> &contact : contacts) {
91  cout << "position: " << contact.pos << endl;
92  }
93 }
94 
95 //==============================================================================
96 GTEST_TEST(FCL_GENERAL, general)
97 {
98  // test_general<float>();
99  test_general<double>();
100 }
101 
102 //==============================================================================
103 int main(int argc, char* argv[])
104 {
105  ::testing::InitGoogleTest(&argc, argv);
106  return RUN_ALL_TESTS();
107 }
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::detail::GJKSolver_libccd
collision and distance solver based on libccd library.
Definition: gjk_solver_libccd.h:54
fcl::Quaternion
Eigen::Quaternion< S > Quaternion
Definition: types.h:88
fcl::detail::GJKSolver_libccd::shapeIntersect
FCL_DEPRECATED bool shapeIntersect(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) const
intersection checking between two shapes
fcl::Contact
Contact information returned by collision.
Definition: contact.h:48
max
static T max(T x, T y)
Definition: svm.cpp:52
GTEST_TEST
GTEST_TEST(FCL_GENERAL, general)
Definition: test_fcl_general.cpp:96
fcl::CollisionResult
collision result
Definition: collision_request.h:48
EXPECT_TRUE
#define EXPECT_TRUE(args)
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::CollisionRequest
Parameters for performing collision request.
Definition: collision_request.h:52
fcl::collide
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
main
int main(int argc, char *argv[])
Definition: test_fcl_general.cpp:103
fcl::CollisionResult::getContacts
void getContacts(std::vector< Contact< S >> &contacts_)
get all the contacts
Definition: collision_result-inl.h:107
fcl::Box
Center at zero point, axis aligned box.
Definition: box.h:51
test_general
void test_general()
Definition: test_fcl_general.cpp:49
enable_contact
bool enable_contact
Definition: test_fcl_collision.cpp:75
num_max_contacts
int num_max_contacts
Definition: test_fcl_collision.cpp:74
fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:51
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:49