GCC Code Coverage Report


Directory: ./
File: include/pinocchio/bindings/python/multibody/data.hpp
Date: 2024-08-27 18:20:05
Exec Total Coverage
Lines: 106 123 86.2%
Branches: 107 252 42.5%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015-2024 CNRS INRIA
3 //
4
5 #ifndef __pinocchio_python_multibody_data_hpp__
6 #define __pinocchio_python_multibody_data_hpp__
7
8 #include "pinocchio/multibody/data.hpp"
9 #include "pinocchio/serialization/data.hpp"
10
11 #include <eigenpy/memory.hpp>
12 #include <eigenpy/eigen-to-python.hpp>
13 #include <eigenpy/exception.hpp>
14
15 #include "pinocchio/bindings/python/fwd.hpp"
16 #include "pinocchio/bindings/python/utils/macros.hpp"
17 #include "pinocchio/bindings/python/serialization/serializable.hpp"
18 #include "pinocchio/bindings/python/utils/std-vector.hpp"
19 #include "pinocchio/bindings/python/utils/std-aligned-vector.hpp"
20 #include "pinocchio/bindings/python/utils/copyable.hpp"
21
22 #if EIGENPY_VERSION_AT_MOST(2, 8, 1)
23 EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::Data)
24 #endif
25
26 namespace pinocchio
27 {
28 namespace python
29 {
30 namespace bp = boost::python;
31
32 template<typename Data>
33 struct PickleData : bp::pickle_suite
34 {
35 static bp::tuple getinitargs(const Data &)
36 {
37 return bp::make_tuple();
38 }
39
40 static bp::tuple getstate(const Data & data)
41 {
42 const std::string str(data.saveToString());
43 return bp::make_tuple(bp::str(str));
44 }
45
46 static void setstate(Data & data, bp::tuple tup)
47 {
48 if (bp::len(tup) == 0 || bp::len(tup) > 1)
49 {
50 throw eigenpy::Exception(
51 "Pickle was not able to reconstruct the model from the loaded data.\n"
52 "The pickle data structure contains too many elements.");
53 }
54
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())
58 {
59 const std::string str = obj_as_string;
60 data.loadFromString(str);
61 }
62 else
63 {
64 throw eigenpy::Exception(
65 "Pickle was not able to reconstruct the model from the loaded data.\n"
66 "The entry is not a string.");
67 }
68 }
69
70 20 static bool getstate_manages_dict()
71 {
72 20 return true;
73 }
74 };
75
76 template<typename Data>
77 struct DataPythonVisitor : public boost::python::def_visitor<DataPythonVisitor<Data>>
78 {
79 typedef typename Data::Matrix6 Matrix6;
80 typedef typename Data::Matrix6x Matrix6x;
81 typedef typename Data::Matrix3x Matrix3x;
82 typedef typename Data::Vector3 Vector3;
83
84 public:
85 #define ADD_DATA_PROPERTY(NAME, DOC) PINOCCHIO_ADD_PROPERTY(Data, NAME, DOC)
86
87 #define ADD_DATA_PROPERTY_READONLY(NAME, DOC) PINOCCHIO_ADD_PROPERTY_READONLY(Data, NAME, DOC)
88
89 #define ADD_DATA_PROPERTY_READONLY_BYVALUE(NAME, DOC) \
90 PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Data, NAME, DOC)
91
92 /* --- Exposing C++ API to python through the handler ----------------- */
93 template<class PyClass>
94 20 void visit(PyClass & cl) const
95 {
96
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
20 cl.def(bp::init<>(bp::arg("self"), "Default constructor."))
97
3/6
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
40 .def(bp::init<const context::Model &>(
98 bp::args("self", "model"), "Constructs a data structure from a given model."))
99
100
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
101 joints,
102 "Vector of JointData associated to each JointModel stored in the related model.")
103
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
104 a, "Vector of joint accelerations expressed in the local frame of the joint.")
105
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
106 oa, "Joint spatial acceleration expressed at the origin of the world frame.")
107
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
108 a_gf, "Joint spatial acceleration containing also the contribution of "
109 "the gravity acceleration")
110
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
111 oa_gf, "Joint spatial acceleration containing also the contribution of the gravity "
112 "acceleration, but expressed at the origin of the world frame.")
113
114
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
115 v, "Vector of joint velocities expressed in the local frame of the joint.")
116
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(ov, "Vector of joint velocities expressed at the origin of the world.")
117
118
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(f, "Vector of body forces expressed in the local frame of the joint.")
119
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(of, "Vector of body forces expressed at the origin of the world.")
120
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
121 of_augmented, "Vector of body forces expressed at the origin of the "
122 "world, in the context of lagrangian formulation")
123
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
124 h, "Vector of spatial momenta expressed in the local frame of the joint.")
125
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(oh, "Vector of spatial momenta expressed at the origin of the world.")
126
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(oMi, "Body absolute placement (wrt world)")
127
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(oMf, "frames absolute placement (wrt world)")
128
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(liMi, "Body relative placement (wrt parent)")
129
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(tau, "Joint torques (output of RNEA)")
130
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(nle, "Non Linear Effects (output of nle algorithm)")
131
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(ddq, "Joint accelerations (output of ABA)")
132
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(Ycrb, "Inertia of the sub-tree composit rigid body")
133
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
134 oYcrb, "Composite Rigid Body Inertia of the sub-tree expressed in the "
135 "WORLD coordinate system.")
136
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(Yaba, "Articulated Body Inertia of the sub-tree")
137
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
138 oYaba,
139 "Articulated Body Inertia of the sub-tree expressed in the WORLD coordinate system.")
140
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(oL, "Acceleration propagator.")
141
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(oK, "Inverse articulated inertia.")
142
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(M, "The joint space inertia matrix")
143
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(Minv, "The inverse of the joint space inertia matrix")
144
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
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
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(g, "Vector of generalized gravity (dim model.nv).")
148
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(Fcrb, "Spatial forces set, used in CRBA")
149
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(lastChild, "Index of the last child (for CRBA)")
150
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(nvSubtree, "Dimension of the subtree motion space (for CRBA)")
151
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(U, "Joint Inertia square root (upper triangle)")
152
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(D, "Diagonal of UDUT inertia decomposition")
153
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(parents_fromRow, "First previous non-zero row in M (used in Cholesky)")
154
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
155 nvSubtree_fromRow, "Subtree of the current row index (used in Cholesky)")
156
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(J, "Jacobian of joint placement")
157
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(dJ, "Time variation of the Jacobian of joint placement (data.J).")
158
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(iMf, "Body placement wrt to algorithm end effector.")
159
160
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(Ivx, "Right variation of the inertia matrix.")
161
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(vxI, "Left variation of the inertia matrix.")
162
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
163 B, "Combined variations of the inertia matrix consistent with Christoffel symbols.")
164
165
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
166 Ag, "Centroidal matrix which maps from joint velocity to the centroidal momentum.")
167
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(dAg, "Time derivative of the centroidal momentum matrix Ag.")
168
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
169 hg, "Centroidal momentum (expressed in the frame centered at the CoM "
170 "and aligned with the world frame).")
171
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
172 dhg, "Centroidal momentum time derivative (expressed in the frame "
173 "centered at the CoM and aligned with the world frame).")
174
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(Ig, "Centroidal Composite Rigid Body Inertia.")
175
176
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(com, "CoM position of the subtree starting at joint index i.")
177
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(vcom, "CoM velocity of the subtree starting at joint index i.")
178
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(acom, "CoM acceleration of the subtree starting at joint index i.")
179
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(mass, "Mass of the subtree starting at joint index i.")
180
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(Jcom, "Jacobian of center of mass.")
181
182
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
183 dAdq,
184 "Variation of the spatial acceleration set with respect to the joint configuration.")
185
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
186 dAdv, "Variation of the spatial acceleration set with respect to the joint velocity.")
187
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
188 dHdq, "Variation of the spatial momenta set with respect to the joint configuration.")
189
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
190 dFdq, "Variation of the force set with respect to the joint configuration.")
191
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(dFdv, "Variation of the force set with respect to the joint velocity.")
192
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
193 dFda, "Variation of the force set with respect to the joint acceleration.")
194
195
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
196 dtau_dq, "Partial derivative of the joint torque vector with respect "
197 "to the joint configuration.")
198
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
199 dtau_dv,
200 "Partial derivative of the joint torque vector with respect to the joint velocity.")
201
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
202 ddq_dq, "Partial derivative of the joint acceleration vector with "
203 "respect to the joint configuration.")
204
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
205 ddq_dv, "Partial derivative of the joint acceleration vector with "
206 "respect to the joint velocity.")
207
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
208 ddq_dtau,
209 "Partial derivative of the joint acceleration vector with respect to the joint torque.")
210
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
211 dvc_dq, "Partial derivative of the constraint velocity vector with "
212 "respect to the joint configuration.")
213
214
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
215 dac_dq, "Partial derivative of the contact acceleration vector with "
216 "respect to the joint configuration.")
217
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
218 dac_dv, "Partial derivative of the contact acceleration vector vector "
219 "with respect to the joint velocity.")
220
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
221 dac_da, "Partial derivative of the contact acceleration vector vector "
222 "with respect to the joint acceleration.")
223
224
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(osim, "Operational space inertia matrix.")
225
226
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 .ADD_DATA_PROPERTY_READONLY_BYVALUE(
227 dlambda_dq, "Partial derivative of the contact force vector with "
228 "respect to the joint configuration.")
229
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 .ADD_DATA_PROPERTY_READONLY_BYVALUE(
230 dlambda_dv,
231 "Partial derivative of the contact force vector with respect to the joint velocity.")
232
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 .ADD_DATA_PROPERTY_READONLY_BYVALUE(
233 dlambda_dtau,
234 "Partial derivative of the contact force vector with respect to the torque.")
235
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
236 kinetic_energy, "Kinetic energy in [J] computed by computeKineticEnergy")
237
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
238 potential_energy, "Potential energy in [J] computed by computePotentialEnergy")
239
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
240 mechanical_energy,
241 "Mechanical energy in [J] of the system computed by computeMechanicalEnergy")
242
243
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(lambda_c, "Lagrange Multipliers linked to contact forces")
244
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(impulse_c, "Lagrange Multipliers linked to contact impulses")
245
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(contact_chol, "Contact Cholesky decomposition.")
246
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
247 primal_dual_contact_solution,
248 "Right hand side vector when solving the contact dynamics KKT problem.")
249
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(
250 lambda_c_prox, "Proximal Lagrange Multipliers used in the computation "
251 "of the Forward Dynamics computations.")
252
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(primal_rhs_contact, "Primal RHS in contact dynamic equations.")
253
254
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(dq_after, "Generalized velocity after the impact.")
255
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(staticRegressor, "Static regressor.")
256
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(jointTorqueRegressor, "Joint torque regressor.")
257
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(kineticEnergyRegressor, "Kinetic energy regressor.")
258
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .ADD_DATA_PROPERTY(potentialEnergyRegressor, "Potential energy regressor.")
259
260 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
261
1/2
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
20 .def(bp::self == bp::self)
262
1/2
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
20 .def(bp::self != bp::self)
263 #endif
264 ;
265 20 }
266
267 /* --- Expose --------------------------------------------------------- */
268 20 static void expose()
269 {
270 20 bp::class_<Data>(
271 "Data",
272 "Articulated rigid body data related to a Model.\n"
273 "It contains all the data that can be modified by the Pinocchio algorithms.",
274 bp::no_init)
275
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .def(DataPythonVisitor())
276
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .def(CopyableVisitor<Data>())
277 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
278
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .def(SerializableVisitor<Data>())
279
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
20 .def_pickle(PickleData<Data>())
280 #endif
281 ;
282
283 typedef PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) StdVec_Vector3;
284 typedef PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6x) StdVec_Matrix6x;
285 typedef PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) StdVec_Matrix6;
286
287
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
20 StdAlignedVectorPythonVisitor<Vector3, false>::expose(
288 "StdVec_Vector3",
289 eigenpy::details::overload_base_get_item_for_std_vector<StdVec_Vector3>());
290
291
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
20 StdAlignedVectorPythonVisitor<Matrix6x, false>::expose(
292 "StdVec_Matrix6x",
293 eigenpy::details::overload_base_get_item_for_std_vector<StdVec_Matrix6x>());
294
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
20 StdAlignedVectorPythonVisitor<Matrix6, false>::expose(
295 "StdVec_Matrix6",
296 eigenpy::details::overload_base_get_item_for_std_vector<StdVec_Matrix6>());
297
3/6
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 20 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 20 times.
✗ Branch 10 not taken.
20 StdVectorPythonVisitor<std::vector<int>, true>::expose("StdVec_int");
298 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
299 20 serialize<typename StdAlignedVectorPythonVisitor<Vector3, false>::vector_type>();
300 20 serialize<typename StdAlignedVectorPythonVisitor<Matrix6x, false>::vector_type>();
301 #endif
302 20 serialize<std::vector<int>>();
303 20 }
304 };
305
306 } // namespace python
307 } // namespace pinocchio
308
309 #undef ADD_DATA_PROPERTY
310 #undef ADD_DATA_PROPERTY_READONLY
311 #undef ADD_DATA_PROPERTY_READONLY_BYVALUE
312
313 #endif // ifndef __pinocchio_python_multibody_data_hpp__
314