math.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 #include <eigenpy/geometry.hpp>
37 
38 #include <hpp/fcl/fwd.hh>
39 #include <hpp/fcl/math/transform.h>
40 
41 #include "fcl.hh"
42 
43 #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
44 #include "doxygen_autodoc/hpp/fcl/math/transform.h"
45 #endif
46 
47 using namespace boost::python;
48 using namespace hpp::fcl;
49 
50 namespace dv = doxygen::visitor;
51 
53  static Triangle::index_type getitem(const Triangle& t, int i) {
54  if (i >= 3 || i <= -3)
55  PyErr_SetString(PyExc_IndexError, "Index out of range");
56  return t[static_cast<hpp::fcl::Triangle::index_type>(i % 3)];
57  }
58  static void setitem(Triangle& t, int i, Triangle::index_type v) {
59  if (i >= 3 || i <= -3)
60  PyErr_SetString(PyExc_IndexError, "Index out of range");
61  t[static_cast<hpp::fcl::Triangle::index_type>(i % 3)] = v;
62  }
63 };
64 
65 void exposeMaths() {
67 
68  if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
70  if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
72 
73  eigenpy::enableEigenPySpecific<Matrix3f>();
74  eigenpy::enableEigenPySpecific<Vec3f>();
75 
76  class_<Transform3f>("Transform3f", doxygen::class_doc<Transform3f>(), no_init)
77  .def(dv::init<Transform3f>())
78  .def(dv::init<Transform3f, const Matrix3f::MatrixBase&,
79  const Vec3f::MatrixBase&>())
80  .def(dv::init<Transform3f, const Quaternion3f&,
81  const Vec3f::MatrixBase&>())
82  .def(dv::init<Transform3f, const Matrix3f&>())
83  .def(dv::init<Transform3f, const Quaternion3f&>())
84  .def(dv::init<Transform3f, const Vec3f&>())
85  .def(dv::init<Transform3f, const Transform3f&>())
86 
87  .def(dv::member_func("getQuatRotation", &Transform3f::getQuatRotation))
88  .def("getTranslation", &Transform3f::getTranslation,
89  doxygen::member_func_doc(&Transform3f::getTranslation),
90  return_value_policy<copy_const_reference>())
91  .def("getRotation", &Transform3f::getRotation,
92  return_value_policy<copy_const_reference>())
93  .def("isIdentity", &Transform3f::isIdentity,
94  (bp::arg("self"),
95  bp::arg("prec") = Eigen::NumTraits<FCL_REAL>::dummy_precision()),
96  doxygen::member_func_doc(&Transform3f::getTranslation))
97 
98  .def(dv::member_func("setQuatRotation", &Transform3f::setQuatRotation))
99  .def("setTranslation", &Transform3f::setTranslation<Vec3f>)
100  .def("setRotation", &Transform3f::setRotation<Matrix3f>)
101  .def(dv::member_func("setTransform",
102  &Transform3f::setTransform<Matrix3f, Vec3f>))
103  .def(dv::member_func(
104  "setTransform",
105  static_cast<void (Transform3f::*)(const Quaternion3f&, const Vec3f&)>(
106  &Transform3f::setTransform)))
107  .def(dv::member_func("setIdentity", &Transform3f::setIdentity))
108  .def(dv::member_func("Identity", &Transform3f::Identity))
109  .staticmethod("Identity")
110 
111  .def(dv::member_func("transform", &Transform3f::transform<Vec3f>))
112  .def("inverseInPlace", &Transform3f::inverseInPlace,
113  return_internal_reference<>(),
114  doxygen::member_func_doc(&Transform3f::inverseInPlace))
115  .def(dv::member_func("inverse", &Transform3f::inverse))
116  .def(dv::member_func("inverseTimes", &Transform3f::inverseTimes))
117 
118  .def(self * self)
119  .def(self *= self)
120  .def(self == self)
121  .def(self != self);
122 
123  class_<Triangle>("Triangle", no_init)
124  .def(dv::init<Triangle>())
127  .def("__getitem__", &TriangleWrapper::getitem)
128  .def("__setitem__", &TriangleWrapper::setitem)
129  .def(dv::member_func("set", &Triangle::set))
130  .def(dv::member_func("size", &Triangle::size))
131  .staticmethod("size")
132  .def(self == self);
133 
135  std::vector<Vec3f> >()) {
136  class_<std::vector<Vec3f> >("StdVec_Vec3f")
137  .def(vector_indexing_suite<std::vector<Vec3f> >());
138  }
140  std::vector<Triangle> >()) {
141  class_<std::vector<Triangle> >("StdVec_Triangle")
142  .def(vector_indexing_suite<std::vector<Triangle> >());
143  }
144 }
eigenpy::exposeAngleAxis
void EIGENPY_DLLAPI exposeAngleAxis()
boost::python
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
eigenpy::exposeQuaternion
void EIGENPY_DLLAPI exposeQuaternion()
TriangleWrapper::getitem
static Triangle::index_type getitem(const Triangle &t, int i)
Definition: math.cc:53
eigenpy.hpp
eigenpy::enableEigenPy
void EIGENPY_DLLAPI enableEigenPy()
hpp::fcl::Triangle::index_type
std::size_t index_type
Definition: data_types.h:98
eigenpy::register_symbolic_link_to_registered_type
bool register_symbolic_link_to_registered_type()
doxygen::visitor
Definition: doxygen-boost.hh:12
fcl.hh
doxygen::def
void def(const char *name, Func func)
Definition: doxygen-boost.hh:106
TriangleWrapper
Definition: math.cc:52
doxygen::visitor::member_func
member_func_impl< function_type > member_func(const char *name, const function_type &function)
Definition: doxygen-boost.hh:49
t
tuple t
hpp::fcl
Definition: broadphase_bruteforce.h:45
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
TriangleWrapper::setitem
static void setitem(Triangle &t, int i, Triangle::index_type v)
Definition: math.cc:58
transform.h
fwd.hh
exposeMaths
void exposeMaths()
Definition: math.cc:65
hpp::fcl::Triangle
Triangle with 3 indices for points.
Definition: data_types.h:96
geometry.hpp
obb.v
list v
Definition: obb.py:48
hpp::fcl::Quaternion3f
Eigen::Quaternion< FCL_REAL > Quaternion3f
Definition: transform.h:46
doxygen::member_func_doc
const char * member_func_doc(FuncPtr)
Definition: doxygen.hh:33


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