distance.cc
Go to the documentation of this file.
1 //
2 // Software License Agreement (BSD License)
3 //
4 // Copyright (c) 2019 CNRS-LAAS INRIA
5 // Author: Joseph Mirabel
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 CNRS-LAAS. 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 #include <eigenpy/eigenpy.hpp>
36 
37 #include "fcl.hh"
38 
39 #include <hpp/fcl/fwd.hh>
40 #include <hpp/fcl/distance.h>
41 
42 #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
43 #include "doxygen_autodoc/functions.h"
44 #include "doxygen_autodoc/hpp/fcl/collision_data.h"
45 #endif
46 
47 using namespace boost::python;
48 using namespace hpp::fcl;
49 
50 namespace dv = doxygen::visitor;
51 
53  static Vec3f getNearestPoint1(const DistanceResult& res) {
54  return res.nearest_points[0];
55  }
56  static Vec3f getNearestPoint2(const DistanceResult& res) {
57  return res.nearest_points[1];
58  }
59 };
60 
62  if (!eigenpy::register_symbolic_link_to_registered_type<DistanceRequest>()) {
63  class_<DistanceRequest, bases<QueryRequest> >(
64  "DistanceRequest", doxygen::class_doc<DistanceRequest>(),
65  init<optional<bool, FCL_REAL, FCL_REAL> >(
66  (arg("self"), arg("enable_nearest_points"), arg("rel_err"),
67  arg("abs_err")),
68  "Constructor"))
69  .DEF_RW_CLASS_ATTRIB(DistanceRequest, enable_nearest_points)
70  .DEF_RW_CLASS_ATTRIB(DistanceRequest, rel_err)
71  .DEF_RW_CLASS_ATTRIB(DistanceRequest, abs_err);
72  }
73 
75  std::vector<DistanceRequest> >()) {
76  class_<std::vector<DistanceRequest> >("StdVec_DistanceRequest")
77  .def(vector_indexing_suite<std::vector<DistanceRequest> >());
78  }
79 
80  if (!eigenpy::register_symbolic_link_to_registered_type<DistanceResult>()) {
81  class_<DistanceResult, bases<QueryResult> >(
82  "DistanceResult", doxygen::class_doc<DistanceResult>(), no_init)
83  .def(dv::init<DistanceResult>())
84  .DEF_RW_CLASS_ATTRIB(DistanceResult, min_distance)
85  .DEF_RW_CLASS_ATTRIB(DistanceResult, normal)
86  //.def_readwrite ("nearest_points", &DistanceResult::nearest_points)
87  .def("getNearestPoint1", &DistanceRequestWrapper::getNearestPoint1,
88  doxygen::class_attrib_doc<DistanceResult>("nearest_points"))
89  .def("getNearestPoint2", &DistanceRequestWrapper::getNearestPoint2,
90  doxygen::class_attrib_doc<DistanceResult>("nearest_points"))
92  .DEF_RO_CLASS_ATTRIB(DistanceResult, o2)
93  .DEF_RW_CLASS_ATTRIB(DistanceResult, b1)
94  .DEF_RW_CLASS_ATTRIB(DistanceResult, b2)
95 
96  .def("clear", &DistanceResult::clear,
97  doxygen::member_func_doc(&DistanceResult::clear));
98  }
99 
101  std::vector<DistanceResult> >()) {
102  class_<std::vector<DistanceResult> >("StdVec_DistanceResult")
103  .def(vector_indexing_suite<std::vector<DistanceResult> >());
104  }
105 
106  doxygen::def(
107  "distance",
108  static_cast<FCL_REAL (*)(const CollisionObject*, const CollisionObject*,
109  const DistanceRequest&, DistanceResult&)>(
110  &distance));
111  doxygen::def(
112  "distance",
113  static_cast<FCL_REAL (*)(const CollisionGeometry*, const Transform3f&,
114  const CollisionGeometry*, const Transform3f&,
116 
117  class_<ComputeDistance>("ComputeDistance",
118  doxygen::class_doc<ComputeDistance>(), no_init)
119  .def(dv::init<ComputeDistance, const CollisionGeometry*,
120  const CollisionGeometry*>())
121  .def("__call__",
122  static_cast<FCL_REAL (ComputeDistance::*)(
123  const Transform3f&, const Transform3f&, DistanceRequest&,
124  DistanceResult&) const>(&ComputeDistance::operator()));
125 }
boost::python
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
DistanceRequestWrapper
Definition: distance.cc:52
eigenpy.hpp
eigenpy::register_symbolic_link_to_registered_type
bool register_symbolic_link_to_registered_type()
exposeDistanceAPI
void exposeDistanceAPI()
Definition: distance.cc:61
distance
double distance(const std::vector< Transform3f > &tf, const BVHModel< BV > &m1, const BVHModel< BV > &m2, bool verbose)
Definition: benchmark.cpp:93
doxygen::visitor
Definition: doxygen-boost.hh:12
fcl.hh
doxygen::def
void def(const char *name, Func func)
Definition: doxygen-boost.hh:106
hpp::fcl::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: collision_object.h:95
DEF_RW_CLASS_ATTRIB
#define DEF_RW_CLASS_ATTRIB(CLASS, ATTRIB)
Definition: python/fwd.hh:29
DistanceRequestWrapper::getNearestPoint2
static Vec3f getNearestPoint2(const DistanceResult &res)
Definition: distance.cc:56
res
res
distance.h
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:215
hpp::fcl
Definition: broadphase_bruteforce.h:45
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::DistanceRequest
request to the distance computation
Definition: collision_data.h:392
hpp::fcl::DistanceResult
distance result
Definition: collision_data.h:420
DistanceRequestWrapper::getNearestPoint1
static Vec3f getNearestPoint1(const DistanceResult &res)
Definition: distance.cc:53
fwd.hh
hpp::fcl::ComputeDistance
Definition: distance.h:98
doxygen::member_func_doc
const char * member_func_doc(FuncPtr)
Definition: doxygen.hh:33
DEF_RO_CLASS_ATTRIB
#define DEF_RO_CLASS_ATTRIB(CLASS, ATTRIB)
Definition: python/fwd.hh:32


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:13