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


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