expose-collision.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2024 INRIA
3 //
4 
5 #include "pinocchio/fwd.hpp"
9 
12 
13 #include <Eigen/Core>
14 
15 namespace pinocchio
16 {
17  namespace python
18  {
19 
20  template<
21  typename Scalar,
22  int Options,
23  template<typename, int> class JointCollectionTpl,
24  typename ConfigVectorType>
25  static std::size_t computeDistances_proxy(
28  const GeometryModel & geom_model,
30  const Eigen::MatrixBase<ConfigVectorType> & q)
31  {
33  }
34 
36  {
37  using namespace Eigen;
38 
39  bp::register_ptr_to_python<std::shared_ptr<hpp::fcl::CollisionGeometry const>>();
40 
41  bp::class_<ComputeCollision>(
42  "ComputeCollision", "Collision function between two geometry objects.\n\n", bp::no_init)
45 
46  bp::class_<ComputeDistance>(
47  "ComputeDistance", "Distance function between two geometry objects.\n\n", bp::no_init)
50 
51  bp::def(
52  "computeCollision",
53  static_cast<bool (*)(
54  const GeometryModel &, GeometryData &, const PairIndex, fcl::CollisionRequest &)>(
56  bp::args("geometry_model", "geometry_data", "pair_index", "collision_request"),
57  "Check if the collision objects of a collision pair for a given Geometry Model and "
58  "Data are in collision.\n"
59  "The collision pair is given by the two index of the collision objects.");
60 
61  bp::def(
62  "computeCollision",
63  static_cast<bool (*)(const GeometryModel &, GeometryData &, const PairIndex)>(
65  bp::args("geometry_model", "geometry_data", "pair_index"),
66  "Check if the collision objects of a collision pair for a given Geometry Model and "
67  "Data are in collision.\n"
68  "The collision pair is given by the two index of the collision objects.");
69 
70  bp::def(
71  "computeCollisions",
72  (bool (*)(const GeometryModel &, GeometryData &, const bool))&computeCollisions,
73  (bp::arg("geometry_model"), bp::arg("geometry_data"),
74  bp::arg("stop_at_first_collision") = false),
75  "Determine if all collision pairs are effectively in collision or not.");
76 
77  bp::def(
78  "computeCollisions", &computeCollisions<double, 0, JointCollectionDefaultTpl, VectorXd>,
79  (bp::arg("model"), bp::arg("data"), bp::arg("geometry_model"), bp::arg("geometry_data"),
80  bp::arg("q"), bp::arg("stop_at_first_collision") = false),
81  "Update the geometry for a given configuration and "
82  "determine if all collision pairs are effectively in collision or not.");
83 
84  bp::def(
85  "computeDistance", &computeDistance,
86  bp::args("geometry_model", "geometry_data", "pair_index"),
87  "Compute the distance between the two geometry objects of a given collision pair for "
88  "a GeometryModel and associated GeometryData.",
89  bp::with_custodian_and_ward_postcall<
90  0, 2, bp::return_value_policy<bp::reference_existing_object>>());
91 
92  bp::def(
93  "computeDistances",
94  (std::size_t (*)(const GeometryModel &, GeometryData &))&computeDistances,
95  bp::args("geometry_model", "geometry_data"),
96  "Compute the distance between each collision pair for a given GeometryModel and "
97  "associated GeometryData.");
98 
99  bp::def(
100  "computeDistances", &computeDistances_proxy<double, 0, JointCollectionDefaultTpl, VectorXd>,
101  bp::args("model", "data", "geometry_model", "geometry_data", "q"),
102  "Update the geometry for a given configuration and "
103  "compute the distance between each collision pair");
104 
105  bp::def(
106  "computeBodyRadius", &computeBodyRadius<double, 0, JointCollectionDefaultTpl>,
107  bp::args("model", "geometry_model", "geometry_data"),
108  "Compute the radius of the geometry volumes attached to every joints.");
109 
111  }
112 
113  } // namespace python
114 } // namespace pinocchio
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::computeCollisions
bool computeCollisions(BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
Definition: broadphase.hpp:34
fwd.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::computeDistance
fcl::DistanceResult & computeDistance(const GeometryModel &geom_model, GeometryData &geom_data, const PairIndex pair_id)
Compute the minimal distance between collision objects of a SINGLE collison pair.
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::GeometryData
Definition: multibody/geometry.hpp:233
collision.hpp
pinocchio::python::Options
@ Options
Definition: expose-contact-inverse-dynamics.cpp:22
distance.hpp
python
pinocchio::PairIndex
Index PairIndex
Definition: multibody/fwd.hpp:29
pinocchio::computeCollision
bool computeCollision(const GeometryModel &geom_model, GeometryData &geom_data, const PairIndex pair_id, fcl::CollisionRequest &collision_request)
Compute the collision status between a SINGLE collision pair. The result is store in the collisionRes...
pinocchio::python::computeDistances_proxy
static std::size_t computeDistances_proxy(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q)
Definition: expose-collision.cpp:25
pinocchio::computeDistances
std::size_t computeDistances(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data)
geometry-functors.hpp
pinocchio::python::StdAlignedVectorPythonVisitor::expose
static void expose(const std::string &class_name, const std::string &doc_string="")
Definition: std-aligned-vector.hpp:43
append-urdf-model-with-another-model.geom_model
geom_model
Definition: append-urdf-model-with-another-model.py:26
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1083
collisions.geom_data
geom_data
Definition: collisions.py:42
std-aligned-vector.hpp
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::python::GeometryFunctorPythonVisitor
Definition: geometry-functors.hpp:19
pinocchio::ModelTpl
Definition: context/generic.hpp:20
collision.hpp
pinocchio::python::exposeCollision
void exposeCollision()
Definition: expose-collision.cpp:35
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::python::exposeBroadphase
void exposeBroadphase()
Definition: expose-broadphase.cpp:80


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:29