GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: python/math.cc Lines: 56 69 81.2 %
Date: 2024-02-09 12:57:42 Branches: 56 120 46.7 %

Line Branch Exec Source
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
52
struct TriangleWrapper {
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
5
void exposeMaths() {
66
5
  eigenpy::enableEigenPy();
67
68
5
  if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
69
5
    eigenpy::exposeQuaternion();
70
5
  if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
71
5
    eigenpy::exposeAngleAxis();
72
73
5
  eigenpy::enableEigenPySpecific<Matrix3f>();
74
5
  eigenpy::enableEigenPySpecific<Vec3f>();
75
76
5
  class_<Transform3f>("Transform3f", doxygen::class_doc<Transform3f>(), no_init)
77
5
      .def(dv::init<Transform3f>())
78
      .def(dv::init<Transform3f, const Matrix3f::MatrixBase&,
79
5
                    const Vec3f::MatrixBase&>())
80
      .def(dv::init<Transform3f, const Quaternion3f&,
81
5
                    const Vec3f::MatrixBase&>())
82
5
      .def(dv::init<Transform3f, const Matrix3f&>())
83
5
      .def(dv::init<Transform3f, const Quaternion3f&>())
84
5
      .def(dv::init<Transform3f, const Vec3f&>())
85
5
      .def(dv::init<Transform3f, const Transform3f&>())
86
87

5
      .def(dv::member_func("getQuatRotation", &Transform3f::getQuatRotation))
88
      .def("getTranslation", &Transform3f::getTranslation,
89
5
           doxygen::member_func_doc(&Transform3f::getTranslation),
90
5
           return_value_policy<copy_const_reference>())
91
      .def("getRotation", &Transform3f::getRotation,
92
5
           return_value_policy<copy_const_reference>())
93
      .def("isIdentity", &Transform3f::isIdentity,
94
           (bp::arg("self"),
95

10
            bp::arg("prec") = Eigen::NumTraits<FCL_REAL>::dummy_precision()),
96

15
           doxygen::member_func_doc(&Transform3f::getTranslation))
97
98

5
      .def(dv::member_func("setQuatRotation", &Transform3f::setQuatRotation))
99
10
      .def("setTranslation", &Transform3f::setTranslation<Vec3f>)
100
5
      .def("setRotation", &Transform3f::setRotation<Matrix3f>)
101
      .def(dv::member_func("setTransform",
102

5
                           &Transform3f::setTransform<Matrix3f, Vec3f>))
103
      .def(dv::member_func(
104
          "setTransform",
105
          static_cast<void (Transform3f::*)(const Quaternion3f&, const Vec3f&)>(
106

5
              &Transform3f::setTransform)))
107

5
      .def(dv::member_func("setIdentity", &Transform3f::setIdentity))
108

5
      .def(dv::member_func("Identity", &Transform3f::Identity))
109
5
      .staticmethod("Identity")
110
111

5
      .def(dv::member_func("transform", &Transform3f::transform<Vec3f>))
112
      .def("inverseInPlace", &Transform3f::inverseInPlace,
113
           return_internal_reference<>(),
114
5
           doxygen::member_func_doc(&Transform3f::inverseInPlace))
115

5
      .def(dv::member_func("inverse", &Transform3f::inverse))
116

5
      .def(dv::member_func("inverseTimes", &Transform3f::inverseTimes))
117
118
5
      .def(self * self)
119
5
      .def(self *= self)
120
5
      .def(self == self)
121
5
      .def(self != self);
122
123
5
  class_<Triangle>("Triangle", no_init)
124
5
      .def(dv::init<Triangle>())
125
      .def(dv::init<Triangle, Triangle::index_type, Triangle::index_type,
126
5
                    Triangle::index_type>())
127
5
      .def("__getitem__", &TriangleWrapper::getitem)
128
5
      .def("__setitem__", &TriangleWrapper::setitem)
129

5
      .def(dv::member_func("set", &Triangle::set))
130

5
      .def(dv::member_func("size", &Triangle::size))
131
5
      .staticmethod("size")
132
5
      .def(self == self);
133
134
5
  if (!eigenpy::register_symbolic_link_to_registered_type<
135
5
          std::vector<Vec3f> >()) {
136
10
    class_<std::vector<Vec3f> >("StdVec_Vec3f")
137
5
        .def(vector_indexing_suite<std::vector<Vec3f> >());
138
  }
139
5
  if (!eigenpy::register_symbolic_link_to_registered_type<
140
5
          std::vector<Triangle> >()) {
141
10
    class_<std::vector<Triangle> >("StdVec_Triangle")
142
5
        .def(vector_indexing_suite<std::vector<Triangle> >());
143
  }
144
5
}