5 #ifndef __pinocchio_python_multibody_data_hpp__ 
    6 #define __pinocchio_python_multibody_data_hpp__ 
   22 #if EIGENPY_VERSION_AT_MOST(2, 8, 1) 
   32     template<
typename Data>
 
   37         return bp::make_tuple();
 
   42         const std::string 
str(
data.saveToString());
 
   43         return bp::make_tuple(bp::str(
str));
 
   48         if (bp::len(tup) == 0 || bp::len(tup) > 1)
 
   51             "Pickle was not able to reconstruct the model from the loaded data.\n" 
   52             "The pickle data structure contains too many elements.");
 
   55         bp::object py_obj = tup[0];
 
   56         boost::python::extract<std::string> obj_as_string(py_obj.ptr());
 
   57         if (obj_as_string.check())
 
   59           const std::string 
str = obj_as_string;
 
   65             "Pickle was not able to reconstruct the model from the loaded data.\n" 
   66             "The entry is not a string.");
 
   76     template<
typename Data>
 
   85 #define ADD_DATA_PROPERTY(NAME, DOC) PINOCCHIO_ADD_PROPERTY(Data, NAME, DOC) 
   87 #define ADD_DATA_PROPERTY_READONLY(NAME, DOC) PINOCCHIO_ADD_PROPERTY_READONLY(Data, NAME, DOC) 
   89 #define ADD_DATA_PROPERTY_READONLY_BYVALUE(NAME, DOC)                                              \ 
   90   PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Data, NAME, DOC) 
   93       template<
class PyClass>
 
   96         cl.def(bp::init<>(bp::arg(
"self"), 
"Default constructor."))
 
   97           .def(bp::init<const context::Model &>(
 
   98             bp::args(
"self", 
"model"), 
"Constructs a data structure from a given model."))
 
  102             "Vector of JointData associated to each JointModel stored in the related model.")
 
  104             a, 
"Vector of joint accelerations expressed in the local frame of the joint.")
 
  106             oa, 
"Joint spatial acceleration expressed at the origin of the world frame.")
 
  108             a_gf, 
"Joint spatial acceleration containing also the contribution of " 
  109                   "the gravity acceleration")
 
  111             oa_gf, 
"Joint spatial acceleration containing also the contribution of the gravity " 
  112                    "acceleration, but expressed at the origin of the world frame.")
 
  115             v, 
"Vector of joint velocities expressed in the local frame of the joint.")
 
  116           .ADD_DATA_PROPERTY(ov, 
"Vector of joint velocities expressed at the origin of the world.")
 
  118           .ADD_DATA_PROPERTY(
f, 
"Vector of body forces expressed in the local frame of the joint.")
 
  119           .ADD_DATA_PROPERTY(of, 
"Vector of body forces expressed at the origin of the world.")
 
  121             of_augmented, 
"Vector of body forces expressed at the origin of the " 
  122                           "world, in the context of lagrangian formulation")
 
  124             h, 
"Vector of spatial momenta expressed in the local frame of the joint.")
 
  125           .ADD_DATA_PROPERTY(oh, 
"Vector of spatial momenta expressed at the origin of the world.")
 
  126           .ADD_DATA_PROPERTY(oMi, 
"Body absolute placement (wrt world)")
 
  127           .ADD_DATA_PROPERTY(oMf, 
"frames absolute placement (wrt world)")
 
  128           .ADD_DATA_PROPERTY(liMi, 
"Body relative placement (wrt parent)")
 
  129           .ADD_DATA_PROPERTY(
tau, 
"Joint torques (output of RNEA)")
 
  130           .ADD_DATA_PROPERTY(
nle, 
"Non Linear Effects (output of nle algorithm)")
 
  131           .ADD_DATA_PROPERTY(ddq, 
"Joint accelerations (output of ABA)")
 
  132           .ADD_DATA_PROPERTY(Ycrb, 
"Inertia of the sub-tree composit rigid body")
 
  134             oYcrb, 
"Composite Rigid Body Inertia of the sub-tree expressed in the " 
  135                    "WORLD coordinate system.")
 
  136           .ADD_DATA_PROPERTY(Yaba, 
"Articulated Body Inertia of the sub-tree")
 
  139             "Articulated Body Inertia of the sub-tree expressed in the WORLD coordinate system.")
 
  140           .ADD_DATA_PROPERTY(oL, 
"Acceleration propagator.")
 
  141           .ADD_DATA_PROPERTY(oK, 
"Inverse articulated inertia.")
 
  142           .ADD_DATA_PROPERTY(
M, 
"The joint space inertia matrix")
 
  143           .ADD_DATA_PROPERTY(Minv, 
"The inverse of the joint space inertia matrix")
 
  145             C, 
"The Coriolis C(q,v) matrix such that the Coriolis effects are " 
  146                "given by c(q,v) = C(q,v)v")
 
  147           .ADD_DATA_PROPERTY(g, 
"Vector of generalized gravity (dim model.nv).")
 
  148           .ADD_DATA_PROPERTY(Fcrb, 
"Spatial forces set, used in CRBA")
 
  149           .ADD_DATA_PROPERTY(lastChild, 
"Index of the last child (for CRBA)")
 
  150           .ADD_DATA_PROPERTY(nvSubtree, 
"Dimension of the subtree motion space (for CRBA)")
 
  151           .ADD_DATA_PROPERTY(
U, 
"Joint Inertia square root (upper triangle)")
 
  152           .ADD_DATA_PROPERTY(
D, 
"Diagonal of UDUT inertia decomposition")
 
  155             "Each element of this vector corresponds to the ordered list of indexes " 
  156             "belonging to the supporting tree of the given index at the row level. " 
  157             "It may be helpful to retrieve the sparsity pattern through it.")
 
  158           .ADD_DATA_PROPERTY(parents_fromRow, 
"First previous non-zero row in M (used in Cholesky)")
 
  160             mimic_parents_fromRow,
 
  161             "First previous non-zero row belonging to a mimic joint in M (used in Jacobian).")
 
  163             non_mimic_parents_fromRow,
 
  164             "First previous non-zero row belonging to a non mimic joint in M (used in Jacobian).")
 
  166             idx_vExtended_to_idx_v_fromRow,
 
  167             "Extended model mapping of the joint rows " 
  168             "(idx_vExtended_to_idx_v_fromRow[idx_vExtended] = idx_v)")
 
  170             nvSubtree_fromRow, 
"Subtree of the current row index (used in Cholesky)")
 
  172             mimic_subtree_joint, 
"When mimic joints are in the tree, this will store the index of " 
  173                                  "the first non mimic child of each mimic joint. (useful in crba)")
 
  174           .ADD_DATA_PROPERTY(
J, 
"Jacobian of joint placement")
 
  175           .ADD_DATA_PROPERTY(dJ, 
"Time variation of the Jacobian of joint placement (data.J).")
 
  176           .ADD_DATA_PROPERTY(iMf, 
"Body placement wrt to algorithm end effector.")
 
  178           .ADD_DATA_PROPERTY(Ivx, 
"Right variation of the inertia matrix.")
 
  179           .ADD_DATA_PROPERTY(vxI, 
"Left variation of the inertia matrix.")
 
  181             B, 
"Combined variations of the inertia matrix consistent with Christoffel symbols.")
 
  184             Ag, 
"Centroidal matrix which maps from joint velocity to the centroidal momentum.")
 
  185           .ADD_DATA_PROPERTY(dAg, 
"Time derivative of the centroidal momentum matrix Ag.")
 
  187             hg, 
"Centroidal momentum (expressed in the frame centered at the CoM " 
  188                 "and aligned with the world frame).")
 
  190             dhg, 
"Centroidal momentum time derivative (expressed in the frame " 
  191                  "centered at the CoM and aligned with the world frame).")
 
  192           .ADD_DATA_PROPERTY(Ig, 
"Centroidal Composite Rigid Body Inertia.")
 
  194           .ADD_DATA_PROPERTY(
com, 
"CoM position of the subtree starting at joint index i.")
 
  195           .ADD_DATA_PROPERTY(vcom, 
"CoM velocity of the subtree starting at joint index i.")
 
  196           .ADD_DATA_PROPERTY(acom, 
"CoM acceleration of the subtree starting at joint index i.")
 
  197           .ADD_DATA_PROPERTY(
mass, 
"Mass of the subtree starting at joint index i.")
 
  198           .ADD_DATA_PROPERTY(Jcom, 
"Jacobian of center of mass.")
 
  202             "Variation of the spatial acceleration set with respect to the joint configuration.")
 
  204             dAdv, 
"Variation of the spatial acceleration set with respect to the joint velocity.")
 
  206             dHdq, 
"Variation of the spatial momenta set with respect to the joint configuration.")
 
  208             dFdq, 
"Variation of the force set with respect to the joint configuration.")
 
  209           .ADD_DATA_PROPERTY(dFdv, 
"Variation of the force set with respect to the joint velocity.")
 
  211             dFda, 
"Variation of the force set with respect to the joint acceleration.")
 
  214             dtau_dq, 
"Partial derivative of the joint torque vector with respect " 
  215                      "to the joint configuration.")
 
  218             "Partial derivative of the joint torque vector with respect to the joint velocity.")
 
  220             ddq_dq, 
"Partial derivative of the joint acceleration vector with " 
  221                     "respect to the joint configuration.")
 
  223             ddq_dv, 
"Partial derivative of the joint acceleration vector with " 
  224                     "respect to the joint velocity.")
 
  227             "Partial derivative of the joint acceleration vector with respect to the joint torque.")
 
  229             dvc_dq, 
"Partial derivative of the constraint velocity vector with " 
  230                     "respect to the joint configuration.")
 
  233             dac_dq, 
"Partial derivative of the contact acceleration vector with " 
  234                     "respect to the joint configuration.")
 
  236             dac_dv, 
"Partial derivative of the contact acceleration vector vector " 
  237                     "with respect to the joint velocity.")
 
  239             dac_da, 
"Partial derivative of the contact acceleration vector vector " 
  240                     "with respect to the joint acceleration.")
 
  242           .ADD_DATA_PROPERTY(osim, 
"Operational space inertia matrix.")
 
  244           .ADD_DATA_PROPERTY_READONLY_BYVALUE(
 
  245             dlambda_dq, 
"Partial derivative of the contact force vector with " 
  246                         "respect to the joint configuration.")
 
  247           .ADD_DATA_PROPERTY_READONLY_BYVALUE(
 
  249             "Partial derivative of the contact force vector with respect to the joint velocity.")
 
  250           .ADD_DATA_PROPERTY_READONLY_BYVALUE(
 
  252             "Partial derivative of the contact force vector with respect to the torque.")
 
  254             kinetic_energy, 
"Kinetic energy in [J] computed by computeKineticEnergy")
 
  256             potential_energy, 
"Potential energy in [J] computed by computePotentialEnergy")
 
  259             "Mechanical energy in [J] of the system computed by computeMechanicalEnergy")
 
  261           .ADD_DATA_PROPERTY(lambda_c, 
"Lagrange Multipliers linked to contact forces")
 
  262           .ADD_DATA_PROPERTY(impulse_c, 
"Lagrange Multipliers linked to contact impulses")
 
  263           .ADD_DATA_PROPERTY(contact_chol, 
"Contact Cholesky decomposition.")
 
  265             primal_dual_contact_solution,
 
  266             "Right hand side vector when solving the contact dynamics KKT problem.")
 
  268             lambda_c_prox, 
"Proximal Lagrange Multipliers used in the computation " 
  269                            "of the Forward Dynamics computations.")
 
  270           .ADD_DATA_PROPERTY(primal_rhs_contact, 
"Primal RHS in contact dynamic equations.")
 
  272           .ADD_DATA_PROPERTY(dq_after, 
"Generalized velocity after the impact.")
 
  273           .ADD_DATA_PROPERTY(staticRegressor, 
"Static regressor.")
 
  274           .ADD_DATA_PROPERTY(jointTorqueRegressor, 
"Joint torque regressor.")
 
  275           .ADD_DATA_PROPERTY(kineticEnergyRegressor, 
"Kinetic energy regressor.")
 
  276           .ADD_DATA_PROPERTY(potentialEnergyRegressor, 
"Potential energy regressor.")
 
  278 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS 
  279           .def(bp::self == bp::self)
 
  280           .def(bp::self != bp::self)
 
  284         bp::register_ptr_to_python<std::shared_ptr<Data>>();
 
  292           "Articulated rigid body data related to a Model.\n" 
  293           "It contains all the data that can be modified by the Pinocchio algorithms.",
 
  297 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION 
  319 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION 
  320         serialize<typename StdAlignedVectorPythonVisitor<Vector3, false>::vector_type>();
 
  321         serialize<typename StdAlignedVectorPythonVisitor<Matrix6x, false>::vector_type>();
 
  323         serialize<std::vector<int>>();
 
  330 #undef ADD_DATA_PROPERTY 
  331 #undef ADD_DATA_PROPERTY_READONLY 
  332 #undef ADD_DATA_PROPERTY_READONLY_BYVALUE 
  334 #endif // ifndef __pinocchio_python_multibody_data_hpp__