GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: include/pinocchio/bindings/python/multibody/geometry-data.hpp Lines: 45 45 100.0 %
Date: 2024-01-23 21:41:47 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
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::GeometryData)
19
20
namespace pinocchio
21
{
22
  namespace python
23
  {
24
    namespace bp = boost::python;
25
26
    /* --- COLLISION PAIR --------------------------------------------------- */
27
    /* --- COLLISION PAIR --------------------------------------------------- */
28
    /* --- COLLISION PAIR --------------------------------------------------- */
29
    struct CollisionPairPythonVisitor
30
    : public boost::python::def_visitor<CollisionPairPythonVisitor>
31
    {
32
19
      static void expose()
33
      {
34
19
        bp::class_<CollisionPair> ("CollisionPair",
35
                                   "Pair of ordered index defining a pair of collisions",
36
                                   bp::no_init)
37
19
        .def(bp::init<>
38
38
             (bp::args("self"),
39
19
              "Empty constructor."))
40
19
        .def(bp::init<const GeomIndex &, const GeomIndex &>
41
38
             (bp::args("self","index1", "index2"),
42
19
              "Initializer of collision pair."))
43
19
        .def(PrintableVisitor<CollisionPair>())
44
19
        .def(CopyableVisitor<CollisionPair>())
45
19
        .def(bp::self == bp::self)
46
19
        .def(bp::self != bp::self)
47
19
        .def_readwrite("first",&CollisionPair::first)
48
19
        .def_readwrite("second",&CollisionPair::second);
49
50

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

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

38
        .def("setGeometryCollisionStatus",
107
             &GeometryData::setGeometryCollisionStatus,
108
             bp::args("self","geom_model","geom_id","enable_collision"),
109
             "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.")
110

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

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

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

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

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

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