| Directory: | ./ |
|---|---|
| File: | bindings/python/module.cpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 74 | 76 | 97.4% |
| Branches: | 110 | 212 | 51.9% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2015-2022 CNRS INRIA | ||
| 3 | // | ||
| 4 | |||
| 5 | #include "pinocchio/bindings/python/fwd.hpp" | ||
| 6 | #include "pinocchio/multibody/fwd.hpp" | ||
| 7 | #include "pinocchio/utils/version.hpp" | ||
| 8 | #include "pinocchio/bindings/python/utils/version.hpp" | ||
| 9 | #include "pinocchio/bindings/python/utils/dependencies.hpp" | ||
| 10 | #include "pinocchio/bindings/python/utils/registration.hpp" | ||
| 11 | |||
| 12 | #include "pinocchio/bindings/python/utils/std-vector.hpp" | ||
| 13 | #include "pinocchio/spatial/cartesian-axis.hpp" | ||
| 14 | #include "pinocchio/bindings/python/serialization/serialization.hpp" | ||
| 15 | |||
| 16 | #include <eigenpy/eigenpy.hpp> | ||
| 17 | #include <eigenpy/optional.hpp> | ||
| 18 | |||
| 19 | namespace bp = boost::python; | ||
| 20 | using namespace pinocchio::python; | ||
| 21 | |||
| 22 |
2/4✓ Branch 0 taken 69 times.
✗ Branch 1 not taken.
✓ Branch 3 taken 69 times.
✗ Branch 4 not taken.
|
276 | BOOST_PYTHON_MODULE(PINOCCHIO_PYTHON_MODULE_NAME) |
| 23 | { | ||
| 24 | 138 | bp::docstring_options module_docstring_options(true, true, false); | |
| 25 | |||
| 26 |
5/10✓ Branch 2 taken 69 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 69 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 69 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 69 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 69 times.
✗ Branch 15 not taken.
|
138 | bp::scope().attr("__version__") = pinocchio::printVersion(); |
| 27 |
4/8✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 69 times.
✗ Branch 11 not taken.
|
138 | bp::scope().attr("__raw_version__") = bp::str(PINOCCHIO_VERSION); |
| 28 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | eigenpy::enableEigenPy(); |
| 29 | |||
| 30 | // Enable warnings | ||
| 31 |
2/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
|
138 | bp::import("warnings"); |
| 32 | |||
| 33 | #if defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE) \ | ||
| 34 | && defined(PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS) | ||
| 35 |
2/4✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 65 times.
✗ Branch 5 not taken.
|
130 | bp::import("hppfcl"); |
| 36 | #endif | ||
| 37 | |||
| 38 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeEigenTypes(); |
| 39 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
138 | exposeSpecificTypeFeatures(); |
| 40 | |||
| 41 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | eigenpy::OptionalConverter<context::VectorXs, boost::optional>::registration(); |
| 42 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | eigenpy::OptionalConverter<Eigen::Ref<context::VectorXs>, boost::optional>::registration(); |
| 43 | eigenpy::OptionalConverter< | ||
| 44 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | const Eigen::Ref<const context::VectorXs>, boost::optional>::registration(); |
| 45 | |||
| 46 | #if defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE) | ||
| 47 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | eigenpy::StdContainerFromPythonList<std::vector<std::string>>::register_converter(); |
| 48 | #endif | ||
| 49 | |||
| 50 |
4/8✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 69 times.
✗ Branch 11 not taken.
|
138 | bp::scope().attr("ScalarType") = getScalarType(); |
| 51 | |||
| 52 |
5/10✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 69 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 69 times.
✗ Branch 14 not taken.
|
276 | bp::scope().attr("XAxis") = bp::object(bp::handle<>( |
| 53 |
2/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
|
284 | eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::XAxis::vector<context::Scalar>()))); |
| 54 |
5/10✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 69 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 69 times.
✗ Branch 14 not taken.
|
276 | bp::scope().attr("YAxis") = bp::object(bp::handle<>( |
| 55 |
2/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
|
284 | eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::YAxis::vector<context::Scalar>()))); |
| 56 |
5/10✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 69 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 69 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 69 times.
✗ Branch 14 not taken.
|
276 | bp::scope().attr("ZAxis") = bp::object(bp::handle<>( |
| 57 |
2/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 69 times.
✗ Branch 5 not taken.
|
284 | eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::ZAxis::vector<context::Scalar>()))); |
| 58 | |||
| 59 |
3/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 65 times.
✓ Branch 4 taken 4 times.
|
138 | if (!register_symbolic_link_to_registered_type<::pinocchio::ReferenceFrame>()) |
| 60 | { | ||
| 61 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
260 | bp::enum_<::pinocchio::ReferenceFrame>("ReferenceFrame") |
| 62 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("WORLD", ::pinocchio::WORLD) |
| 63 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("LOCAL", ::pinocchio::LOCAL) |
| 64 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("LOCAL_WORLD_ALIGNED", ::pinocchio::LOCAL_WORLD_ALIGNED) |
| 65 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .export_values(); |
| 66 | } | ||
| 67 | |||
| 68 |
3/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 65 times.
✓ Branch 4 taken 4 times.
|
138 | if (!register_symbolic_link_to_registered_type<::pinocchio::KinematicLevel>()) |
| 69 | { | ||
| 70 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
260 | bp::enum_<::pinocchio::KinematicLevel>("KinematicLevel") |
| 71 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("POSITION", ::pinocchio::POSITION) |
| 72 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("VELOCITY", ::pinocchio::VELOCITY) |
| 73 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("ACCELERATION", ::pinocchio::ACCELERATION) |
| 74 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .export_values(); |
| 75 | } | ||
| 76 | |||
| 77 |
3/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 65 times.
✓ Branch 4 taken 4 times.
|
138 | if (!register_symbolic_link_to_registered_type<::pinocchio::Convention>()) |
| 78 | { | ||
| 79 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
260 | bp::enum_<::pinocchio::Convention>("Convention") |
| 80 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("WORLD", ::pinocchio::Convention::WORLD) |
| 81 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("LOCAL", ::pinocchio::Convention::LOCAL); |
| 82 | } | ||
| 83 | |||
| 84 |
3/4✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 65 times.
✓ Branch 4 taken 4 times.
|
138 | if (!register_symbolic_link_to_registered_type<::pinocchio::ArgumentPosition>()) |
| 85 | { | ||
| 86 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
260 | bp::enum_<::pinocchio::ArgumentPosition>("ArgumentPosition") |
| 87 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("ARG0", ::pinocchio::ARG0) |
| 88 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("ARG1", ::pinocchio::ARG1) |
| 89 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("ARG2", ::pinocchio::ARG2) |
| 90 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("ARG3", ::pinocchio::ARG3) |
| 91 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .value("ARG4", ::pinocchio::ARG4) |
| 92 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | .export_values(); |
| 93 | } | ||
| 94 | |||
| 95 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeSE3(); |
| 96 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeForce(); |
| 97 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeMotion(); |
| 98 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeInertia(); |
| 99 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeSymmetric3(); |
| 100 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeJoints(); |
| 101 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeExplog(); |
| 102 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeRpy(); |
| 103 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeLinalg(); |
| 104 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeTridiagonalMatrix(); |
| 105 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeLanczosDecomposition(); |
| 106 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeSkew(); |
| 107 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeLieGroups(); |
| 108 | |||
| 109 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeFrame(); |
| 110 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeModel(); |
| 111 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeData(); |
| 112 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeSampleModels(); |
| 113 | #if defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE) | ||
| 114 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | exposeGeometry(); |
| 115 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | exposeParsers(); |
| 116 | #endif // defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE) | ||
| 117 | |||
| 118 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeAlgorithms(); |
| 119 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeExtras(); |
| 120 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeSerialization(); |
| 121 | |||
| 122 | #if defined(PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS) \ | ||
| 123 | && defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE) | ||
| 124 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | exposeFCL(); |
| 125 |
1/2✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
|
130 | exposeCollision(); |
| 126 | #endif // defined(PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS) && | ||
| 127 | // defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE) | ||
| 128 | |||
| 129 | #if defined(PINOCCHIO_PYTHON_INTERFACE_WITH_OPENMP) \ | ||
| 130 | && defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE) | ||
| 131 | exposePool(); | ||
| 132 | exposeParallelAlgorithms(); | ||
| 133 | #endif | ||
| 134 | |||
| 135 | #if defined(PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS) \ | ||
| 136 | && defined(PINOCCHIO_PYTHON_INTERFACE_WITH_OPENMP) \ | ||
| 137 | && defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE) | ||
| 138 | exposePoolCollision(); | ||
| 139 | exposeParallelCollision(); | ||
| 140 | #endif | ||
| 141 | |||
| 142 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeVersion(); |
| 143 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeDependencies(); |
| 144 |
1/2✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
|
138 | exposeConversions(); |
| 145 | |||
| 146 | typedef std::vector<::pinocchio::VectorXb> StdVec_VectorXb; | ||
| 147 | typedef std::vector<context::MatrixXs> StdVec_MatrixXs; | ||
| 148 | |||
| 149 |
2/4✓ Branch 2 taken 69 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 69 times.
✗ Branch 6 not taken.
|
138 | StdVectorPythonVisitor<StdVec_VectorXb, false>::expose( |
| 150 | ✗ | "StdVec_VectorXb", eigenpy::details::overload_base_get_item_for_std_vector<StdVec_VectorXb>()); | |
| 151 |
2/4✓ Branch 2 taken 69 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 69 times.
✗ Branch 6 not taken.
|
138 | StdVectorPythonVisitor<StdVec_MatrixXs, false>::expose( |
| 152 | ✗ | "StdVec_MatrixXs", eigenpy::details::overload_base_get_item_for_std_vector<StdVec_MatrixXs>()); | |
| 153 | 138 | } | |
| 154 |