GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: include/pinocchio/bindings/python/multibody/geometry-data.hpp Lines: 45 45 100.0 %
Date: 2024-04-26 13:14:21 Branches: 46 92 50.0 %

Line Branch Exec Source
1
//
2
// Copyright (c) 2015-2021 CNRS INRIA
3
//
4
5
#ifndef __pinocchio_python_geometry_data_hpp__
6
#define __pinocchio_python_geometry_data_hpp__
7
8
#include <eigenpy/memory.hpp>
9
10
#include "pinocchio/serialization/geometry.hpp"
11
12
#include "pinocchio/bindings/python/utils/printable.hpp"
13
#include "pinocchio/bindings/python/utils/copyable.hpp"
14
#include "pinocchio/bindings/python/utils/deprecation.hpp"
15
#include "pinocchio/bindings/python/utils/std-vector.hpp"
16
#include "pinocchio/bindings/python/serialization/serializable.hpp"
17
18
#if EIGENPY_VERSION_AT_MOST(2,8,1)
19
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::GeometryData)
20
#endif
21
22
namespace pinocchio
23
{
24
  namespace python
25
  {
26
    namespace bp = boost::python;
27
28
    /* --- COLLISION PAIR --------------------------------------------------- */
29
    /* --- COLLISION PAIR --------------------------------------------------- */
30
    /* --- COLLISION PAIR --------------------------------------------------- */
31
    struct CollisionPairPythonVisitor
32
    : public boost::python::def_visitor<CollisionPairPythonVisitor>
33
    {
34
19
      static void expose()
35
      {
36
19
        bp::class_<CollisionPair> ("CollisionPair",
37
                                   "Pair of ordered index defining a pair of collisions",
38
                                   bp::no_init)
39
19
        .def(bp::init<>
40
38
             (bp::args("self"),
41
19
              "Empty constructor."))
42
19
        .def(bp::init<const GeomIndex &, const GeomIndex &>
43
38
             (bp::args("self","index1", "index2"),
44
19
              "Initializer of collision pair."))
45
19
        .def(PrintableVisitor<CollisionPair>())
46
19
        .def(CopyableVisitor<CollisionPair>())
47
19
        .def(bp::self == bp::self)
48
19
        .def(bp::self != bp::self)
49
19
        .def_readwrite("first",&CollisionPair::first)
50
19
        .def_readwrite("second",&CollisionPair::second);
51
52

19
        StdVectorPythonVisitor<CollisionPair>::expose("StdVec_CollisionPair");
53
19
        serialize< std::vector<CollisionPair> >();
54
19
      }
55
    }; // struct CollisionPairPythonVisitor
56
57
    struct GeometryDataPythonVisitor
58
    : public boost::python::def_visitor< GeometryDataPythonVisitor >
59
    {
60
61
      /* --- Exposing C++ API to python through the handler ----------------- */
62
      template<class PyClass>
63
19
      void visit(PyClass& cl) const
64
      {
65
19
        cl
66
        .def(bp::init<GeometryModel>(bp::args("self","geometry_model"),
67
                                     "Default constructor from a given GeometryModel"))
68
69

19
        .def_readonly("oMg",
70
                      &GeometryData::oMg,
71
                      "Vector of collision objects placement relative to the world frame.\n"
72
                      "note: These quantities have to be updated by calling updateGeometryPlacements.")
73
19
        .def_readonly("activeCollisionPairs",
74
                      &GeometryData::activeCollisionPairs,
75
                      "Vector of active CollisionPairs")
76
77
#ifdef PINOCCHIO_WITH_HPP_FCL
78
19
        .def_readonly("distanceRequests",
79
                      &GeometryData::distanceRequests,
80
                      "Defines which information should be computed by FCL for distance computations")
81
19
        .def_readonly("distanceResults",
82
                      &GeometryData::distanceResults,
83
                      "Vector of distance results.")
84
19
        .def_readonly("collisionRequests",
85
                      &GeometryData::collisionRequests,
86
                      "Defines which information should be computed by FCL for collision computations.\n\n"
87
                      "Note: it is possible to define a security_margin and a break_distance for a collision request.\n"
88
                      "Most likely, for robotics application, these thresholds will be different for each collision pairs\n"
89
                      "(e.g. the two hands can have a large security margin while the two hips cannot.)")
90
19
        .def_readonly("collisionResults",
91
                      &GeometryData::collisionResults,
92
                      "Vector of collision results.")
93
19
        .def_readonly("radius",
94
                      &GeometryData::radius,
95
                      "Vector of radius of bodies, i.e. the distance between the further point of the geometry object from the joint center.\n"
96
                      "note: This radius information might be usuful in continuous collision checking")
97
#endif // PINOCCHIO_WITH_HPP_FCL
98
99
19
        .def("fillInnerOuterObjectMaps",
100
             &GeometryData::fillInnerOuterObjectMaps,
101
             bp::args("self","geometry_model"),
102
             "Fill inner and outer objects maps")
103
38
        .def("activateCollisionPair",
104
             static_cast<void (GeometryData::*)(const PairIndex)>(&GeometryData::activateCollisionPair),
105
             bp::args("self","pair_id"),
106
             "Activate the collsion pair pair_id in geomModel.collisionPairs if it exists.\n"
107
             "note: Only active pairs are check for collision and distance computations.")
108

38
        .def("setGeometryCollisionStatus",
109
             &GeometryData::setGeometryCollisionStatus,
110
             bp::args("self","geom_model","geom_id","enable_collision"),
111
             "Enable or disable collision for the given geometry given by its geometry id with all the other geometries registered in the list of collision pairs.")
112

38
        .def("setActiveCollisionPairs",
113
             &GeometryData::setActiveCollisionPairs,
114
             setActiveCollisionPairs_overload(bp::args("self","geometry_model","collision_map","upper"),
115
                                              "Set the collision pair association from a given input array.\n"
116
                                              "Each entry of the input matrix defines the activation of a given collision pair."))
117

38
        .def("deactivateCollisionPair",
118
             &GeometryData::deactivateCollisionPair,
119
             bp::args("self","pair_id"),
120
             "Deactivate the collsion pair pair_id in geomModel.collisionPairs if it exists.")
121

38
        .def("deactivateAllCollisionPairs",
122
             &GeometryData::deactivateAllCollisionPairs,
123
             bp::args("self"),
124
             "Deactivate all collision pairs.")
125
#ifdef PINOCCHIO_WITH_HPP_FCL
126

38
        .def("setSecurityMargins",
127
             &GeometryData::setSecurityMargins,
128
             setSecurityMargins_overload(bp::args("self","geometry_model","security_margin_map","upper"),
129
                                         "Set the security margin of all the collision request in a row, according to the values stored in the associative map."))
130
#endif // PINOCCHIO_WITH_HPP_FCL
131
132

57
        .def(bp::self == bp::self)
133

57
        .def(bp::self != bp::self)
134
135
        ;
136
137
19
      }
138
139
      /* --- Expose --------------------------------------------------------- */
140
19
      static void expose()
141
      {
142
19
        bp::class_<GeometryData>("GeometryData",
143
                                 "Geometry data linked to a Geometry Model and a Data struct.",
144
                                 bp::no_init)
145
19
        .def(GeometryDataPythonVisitor())
146
19
        .def(PrintableVisitor<GeometryData>())
147
19
        .def(CopyableVisitor<GeometryData>())
148
19
        .def(SerializableVisitor<GeometryData>())
149
        ;
150
151
19
      }
152
153
    protected:
154
155
38
      BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(setActiveCollisionPairs_overload,GeometryData::setActiveCollisionPairs,2,3)
156
19
      BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(setSecurityMargins_overload,GeometryData::setSecurityMargins,2,3)
157
158
    };
159
160
  }} // namespace pinocchio::python
161
162
#endif // ifndef __pinocchio_python_geometry_data_hpp__