Skip to content

Commit

Permalink
Merge pull request #1284 from jcarpent/topic/devel
Browse files Browse the repository at this point in the history
Activate the sharing of memory between C++ and Python
  • Loading branch information
jcarpent authored Aug 31, 2020
2 parents b125aa2 + 3f29ef9 commit 2d4dbb0
Show file tree
Hide file tree
Showing 17 changed files with 357 additions and 178 deletions.
12 changes: 6 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -124,13 +124,15 @@ IF(BUILD_WITH_CASADI_SUPPORT)
ENDIF(BUILD_WITH_CASADI_SUPPORT)

SET(BOOST_REQUIRED_COMPONENTS filesystem serialization system)
SET(BOOST_BUILD_COMPONENTS unit_test_framework)
SET(BOOST_OPTIONAL_COMPONENTS "")

SET_BOOST_DEFAULT_OPTIONS()
EXPORT_BOOST_DEFAULT_OPTIONS()
ADD_PROJECT_DEPENDENCY(Boost REQUIRED COMPONENTS ${BOOST_REQUIRED_COMPONENTS})

IF(BUILD_PYTHON_INTERFACE)
SET(BOOST_OPTIONAL_COMPONENTS ${BOOST_OPTIONAL_COMPONENTS} python)
FINDPYTHON()
ADD_PROJECT_DEPENDENCY(eigenpy 2.2.0 REQUIRED)
SEARCH_FOR_BOOST_PYTHON(REQUIRED)
ADD_PROJECT_DEPENDENCY(eigenpy 2.5.0 REQUIRED)
ENDIF(BUILD_PYTHON_INTERFACE)

IF(BUILD_WITH_HPP_FCL_SUPPORT)
Expand All @@ -154,8 +156,6 @@ IF(BUILD_WITH_HPP_FCL_SUPPORT)
ENDIF(BUILD_PYTHON_INTERFACE)
ENDIF(BUILD_WITH_HPP_FCL_SUPPORT)

SET(BOOST_COMPONENTS ${BOOST_REQUIRED_COMPONENTS} ${BOOST_OPTIONAL_COMPONENTS} ${BOOST_BUILD_COMPONENTS})
SEARCH_FOR_BOOST()
# Enforce the preprocessed version of boost::list and boost::vector
# This information is redundant with the content of include/pinocchio/container/boost-container-limits.hpp
# but it avoids any compilation issue.
Expand Down
82 changes: 44 additions & 38 deletions bindings/python/multibody/data.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,16 @@
// Copyright (c) 2015-2020 CNRS INRIA
//

#ifndef __pinocchio_python_data_hpp__
#define __pinocchio_python_data_hpp__
#ifndef __pinocchio_python_multibody_data_hpp__
#define __pinocchio_python_multibody_data_hpp__

#include <boost/python.hpp>

#include "pinocchio/multibody/data.hpp"
#include "pinocchio/serialization/data.hpp"

#include <eigenpy/memory.hpp>
#include <eigenpy/eigen-to-python.hpp>
#include <eigenpy/exception.hpp>

#include "pinocchio/bindings/python/serialization/serializable.hpp"
Expand Down Expand Up @@ -114,56 +115,56 @@ namespace pinocchio
.ADD_DATA_PROPERTY(oMi,"Body absolute placement (wrt world)")
.ADD_DATA_PROPERTY(oMf,"frames absolute placement (wrt world)")
.ADD_DATA_PROPERTY(liMi,"Body relative placement (wrt parent)")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(tau,"Joint torques (output of RNEA)")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(nle,"Non Linear Effects (output of nle algorithm)")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(ddq,"Joint accelerations (output of ABA)")
.ADD_DATA_PROPERTY(tau,"Joint torques (output of RNEA)")
.ADD_DATA_PROPERTY(nle,"Non Linear Effects (output of nle algorithm)")
.ADD_DATA_PROPERTY(ddq,"Joint accelerations (output of ABA)")
.ADD_DATA_PROPERTY(Ycrb,"Inertia of the sub-tree composit rigid body")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(M,"The joint space inertia matrix")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(Minv,"The inverse of the joint space inertia matrix")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(C,"The Coriolis C(q,v) matrix such that the Coriolis effects are given by c(q,v) = C(q,v)v")
.ADD_DATA_PROPERTY(M,"The joint space inertia matrix")
.ADD_DATA_PROPERTY(Minv,"The inverse of the joint space inertia matrix")
.ADD_DATA_PROPERTY(C,"The Coriolis C(q,v) matrix such that the Coriolis effects are given by c(q,v) = C(q,v)v")
.ADD_DATA_PROPERTY(Fcrb,"Spatial forces set, used in CRBA")
.ADD_DATA_PROPERTY(lastChild,"Index of the last child (for CRBA)")
.ADD_DATA_PROPERTY(nvSubtree,"Dimension of the subtree motion space (for CRBA)")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(U,"Joint Inertia square root (upper triangle)")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(D,"Diagonal of UDUT inertia decomposition")
.ADD_DATA_PROPERTY(U,"Joint Inertia square root (upper triangle)")
.ADD_DATA_PROPERTY(D,"Diagonal of UDUT inertia decomposition")
.ADD_DATA_PROPERTY(parents_fromRow,"First previous non-zero row in M (used in Cholesky)")
.ADD_DATA_PROPERTY(nvSubtree_fromRow,"Subtree of the current row index (used in Cholesky)")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(J,"Jacobian of joint placement")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(dJ,"Time variation of the Jacobian of joint placement (data.J).")
.ADD_DATA_PROPERTY(J,"Jacobian of joint placement")
.ADD_DATA_PROPERTY(dJ,"Time variation of the Jacobian of joint placement (data.J).")
.ADD_DATA_PROPERTY(iMf,"Body placement wrt to algorithm end effector.")

.ADD_DATA_PROPERTY_READONLY_BYVALUE(Ag,
"Centroidal matrix which maps from joint velocity to the centroidal momentum.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(dAg,
"Time derivative of the centroidal momentum matrix Ag.")
.ADD_DATA_PROPERTY_READONLY(hg,
"Centroidal momentum (expressed in the frame centered at the CoM and aligned with the world frame).")
.ADD_DATA_PROPERTY_READONLY(dhg,
"Centroidal momentum time derivative (expressed in the frame centered at the CoM and aligned with the world frame).")
.ADD_DATA_PROPERTY_READONLY(Ig,
"Centroidal Composite Rigid Body Inertia.")
.ADD_DATA_PROPERTY(Ag,
"Centroidal matrix which maps from joint velocity to the centroidal momentum.")
.ADD_DATA_PROPERTY(dAg,
"Time derivative of the centroidal momentum matrix Ag.")
.ADD_DATA_PROPERTY(hg,
"Centroidal momentum (expressed in the frame centered at the CoM and aligned with the world frame).")
.ADD_DATA_PROPERTY(dhg,
"Centroidal momentum time derivative (expressed in the frame centered at the CoM and aligned with the world frame).")
.ADD_DATA_PROPERTY(Ig,
"Centroidal Composite Rigid Body Inertia.")

.ADD_DATA_PROPERTY(com,"CoM position of the subtree starting at joint index i.")
.ADD_DATA_PROPERTY(vcom,"CoM velocity of the subtree starting at joint index i.")
.ADD_DATA_PROPERTY(acom,"CoM acceleration of the subtree starting at joint index i..")
.ADD_DATA_PROPERTY(mass,"Mass of the subtree starting at joint index i.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(Jcom,"Jacobian of center of mass.")
.ADD_DATA_PROPERTY(Jcom,"Jacobian of center of mass.")

.ADD_DATA_PROPERTY_READONLY_BYVALUE(C,"Joint space Coriolis matrix.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(dtau_dq,"Partial derivative of the joint torque vector with respect to the joint configuration.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(dtau_dv,"Partial derivative of the joint torque vector with respect to the joint velocity.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(ddq_dq,"Partial derivative of the joint acceleration vector with respect to the joint configuration.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(ddq_dv,"Partial derivative of the joint acceleration vector with respect to the joint velocity.")
.ADD_DATA_PROPERTY(C,"Joint space Coriolis matrix.")
.ADD_DATA_PROPERTY(dtau_dq,"Partial derivative of the joint torque vector with respect to the joint configuration.")
.ADD_DATA_PROPERTY(dtau_dv,"Partial derivative of the joint torque vector with respect to the joint velocity.")
.ADD_DATA_PROPERTY(ddq_dq,"Partial derivative of the joint acceleration vector with respect to the joint configuration.")
.ADD_DATA_PROPERTY(ddq_dv,"Partial derivative of the joint acceleration vector with respect to the joint velocity.")

.ADD_DATA_PROPERTY_READONLY_BYVALUE(kinetic_energy,"Kinetic energy in [J] computed by computeKineticEnergy")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(potential_energy,"Potential energy in [J] computed by computePotentialEnergy")
.ADD_DATA_PROPERTY(kinetic_energy,"Kinetic energy in [J] computed by computeKineticEnergy")
.ADD_DATA_PROPERTY(potential_energy,"Potential energy in [J] computed by computePotentialEnergy")

.ADD_DATA_PROPERTY_READONLY_BYVALUE(lambda_c,"Lagrange Multipliers linked to contact forces")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(impulse_c,"Lagrange Multipliers linked to contact impulses")
.ADD_DATA_PROPERTY(lambda_c,"Lagrange Multipliers linked to contact forces")
.ADD_DATA_PROPERTY(impulse_c,"Lagrange Multipliers linked to contact impulses")

.ADD_DATA_PROPERTY_READONLY_BYVALUE(dq_after,"Generalized velocity after the impact.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(staticRegressor,"Static regressor.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(jointTorqueRegressor,"Joint torque regressor.")
.ADD_DATA_PROPERTY(dq_after,"Generalized velocity after the impact.")
.ADD_DATA_PROPERTY(staticRegressor,"Static regressor.")
.ADD_DATA_PROPERTY(jointTorqueRegressor,"Joint torque regressor.")

.def(bp::self == bp::self)
.def(bp::self != bp::self)
Expand All @@ -182,13 +183,18 @@ namespace pinocchio
.def(SerializableVisitor<Data>())
.def_pickle(PickleData<Data>());

StdAlignedVectorPythonVisitor<Vector3, true>::expose("StdVec_vec3d");
StdAlignedVectorPythonVisitor<Matrix6x, true>::expose("StdVec_Matrix6x");
typedef PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) StdVec_Vector3;
typedef PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6x) StdVec_Matrix6x;

StdAlignedVectorPythonVisitor<Vector3,false>::expose("StdVec_vec3d")
.def(details::overload_base_get_item_for_std_vector<StdVec_Vector3>());
StdAlignedVectorPythonVisitor<Matrix6x,false>::expose("StdVec_Matrix6x")
.def(details::overload_base_get_item_for_std_vector<StdVec_Matrix6x>());
StdVectorPythonVisitor<int>::expose("StdVec_int");
}

};

}} // namespace pinocchio::python

#endif // ifndef __pinocchio_python_data_hpp__
#endif // ifndef __pinocchio_python_multibody_data_hpp__
Loading

0 comments on commit 2d4dbb0

Please sign in to comment.