pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
joint-planar.hpp
1//
2// Copyright (c) 2015-2020 CNRS INRIA
3// Copyright (c) 2015-2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4//
5
6#ifndef __pinocchio_multibody_joint_planar_hpp__
7#define __pinocchio_multibody_joint_planar_hpp__
8
9#include "pinocchio/macros.hpp"
10#include "pinocchio/multibody/joint/joint-base.hpp"
11#include "pinocchio/spatial/cartesian-axis.hpp"
12#include "pinocchio/multibody/joint-motion-subspace.hpp"
13#include "pinocchio/spatial/motion.hpp"
14#include "pinocchio/spatial/inertia.hpp"
15
16namespace pinocchio
17{
18
19 template<typename Scalar, int Options = context::Options>
20 struct MotionPlanarTpl;
21 typedef MotionPlanarTpl<context::Scalar> MotionPlanar;
22
23 template<typename Scalar, int Options>
24 struct SE3GroupAction<MotionPlanarTpl<Scalar, Options>>
25 {
27 };
28
29 template<typename Scalar, int Options, typename MotionDerived>
34
35 template<typename _Scalar, int _Options>
37 {
38 typedef _Scalar Scalar;
39 enum
40 {
41 Options = _Options
42 };
43 typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
44 typedef Eigen::Matrix<Scalar, 6, 1, Options> Vector6;
45 typedef Eigen::Matrix<Scalar, 4, 4, Options> Matrix4;
46 typedef Eigen::Matrix<Scalar, 6, 6, Options> Matrix6;
47 typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
48 typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
49 typedef Vector3 AngularType;
50 typedef Vector3 LinearType;
51 typedef const Vector3 ConstAngularType;
52 typedef const Vector3 ConstLinearType;
53 typedef Matrix6 ActionMatrixType;
54 typedef Matrix4 HomogeneousMatrixType;
57 enum
58 {
59 LINEAR = 0,
60 ANGULAR = 3
61 };
62 }; // traits MotionPlanarTpl
63
64 template<typename _Scalar, int _Options>
65 struct MotionPlanarTpl : MotionBase<MotionPlanarTpl<_Scalar, _Options>>
66 {
68 MOTION_TYPEDEF_TPL(MotionPlanarTpl);
69
70 typedef CartesianAxis<2> ZAxis;
71
73 {
74 }
75
76 MotionPlanarTpl(const Scalar & x_dot, const Scalar & y_dot, const Scalar & theta_dot)
77 {
78 m_data << x_dot, y_dot, theta_dot;
79 }
80
81 template<typename Vector3Like>
82 MotionPlanarTpl(const Eigen::MatrixBase<Vector3Like> & vj)
83 : m_data(vj)
84 {
86 }
87
88 inline PlainReturnType plain() const
89 {
90 return PlainReturnType(
91 typename PlainReturnType::Vector3(vx(), vy(), Scalar(0)),
92 typename PlainReturnType::Vector3(Scalar(0), Scalar(0), wz()));
93 }
94
95 template<typename Derived>
96 void addTo(MotionDense<Derived> & other) const
97 {
98 other.linear()[0] += vx();
99 other.linear()[1] += vy();
100 other.angular()[2] += wz();
101 }
102
103 template<typename MotionDerived>
104 void setTo(MotionDense<MotionDerived> & other) const
105 {
106 other.linear() << vx(), vy(), (Scalar)0;
107 other.angular() << (Scalar)0, (Scalar)0, wz();
108 }
109
110 template<typename S2, int O2, typename D2>
111 void se3Action_impl(const SE3Tpl<S2, O2> & m, MotionDense<D2> & v) const
112 {
113 v.angular().noalias() = m.rotation().col(2) * wz();
114 v.linear().noalias() = m.rotation().template leftCols<2>() * m_data.template head<2>();
115 v.linear() += m.translation().cross(v.angular());
116 }
117
118 template<typename S2, int O2>
119 MotionPlain se3Action_impl(const SE3Tpl<S2, O2> & m) const
120 {
121 MotionPlain res;
122 se3Action_impl(m, res);
123 return res;
124 }
125
126 template<typename S2, int O2, typename D2>
127 void se3ActionInverse_impl(const SE3Tpl<S2, O2> & m, MotionDense<D2> & v) const
128 {
129 // Linear
130 // TODO: use v.angular() as temporary variable
131 Vector3 v3_tmp;
132 ZAxis::alphaCross(wz(), m.translation(), v3_tmp);
133 v3_tmp[0] += vx();
134 v3_tmp[1] += vy();
135 v.linear().noalias() = m.rotation().transpose() * v3_tmp;
136
137 // Angular
138 v.angular().noalias() = m.rotation().transpose().col(2) * wz();
139 }
140
141 template<typename S2, int O2>
142 MotionPlain se3ActionInverse_impl(const SE3Tpl<S2, O2> & m) const
143 {
144 MotionPlain res;
145 se3ActionInverse_impl(m, res);
146 return res;
147 }
148
149 template<typename M1, typename M2>
150 void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
151 {
152 // Linear
153 ZAxis::alphaCross(-wz(), v.linear(), mout.linear());
154
155 typename M1::ConstAngularType w_in = v.angular();
156 typename M2::LinearType v_out = mout.linear();
157
158 v_out[0] -= w_in[2] * vy();
159 v_out[1] += w_in[2] * vx();
160 v_out[2] += -w_in[1] * vx() + w_in[0] * vy();
161
162 // Angular
163 ZAxis::alphaCross(-wz(), v.angular(), mout.angular());
164 }
165
166 template<typename M1>
167 MotionPlain motionAction(const MotionDense<M1> & v) const
168 {
169 MotionPlain res;
170 motionAction(v, res);
171 return res;
172 }
173
174 const Scalar & vx() const
175 {
176 return m_data[0];
177 }
178 Scalar & vx()
179 {
180 return m_data[0];
181 }
182
183 const Scalar & vy() const
184 {
185 return m_data[1];
186 }
187 Scalar & vy()
188 {
189 return m_data[1];
190 }
191
192 const Scalar & wz() const
193 {
194 return m_data[2];
195 }
196 Scalar & wz()
197 {
198 return m_data[2];
199 }
200
201 const Vector3 & data() const
202 {
203 return m_data;
204 }
205 Vector3 & data()
206 {
207 return m_data;
208 }
209
210 bool isEqual_impl(const MotionPlanarTpl & other) const
211 {
212 return internal::comparison_eq(m_data, other.m_data);
213 }
214
215 protected:
216 Vector3 m_data;
217
218 }; // struct MotionPlanarTpl
219
220 template<typename Scalar, int Options, typename MotionDerived>
221 inline typename MotionDerived::MotionPlain
223 {
224 typename MotionDerived::MotionPlain result(m2);
225 result.linear()[0] += m1.vx();
226 result.linear()[1] += m1.vy();
227
228 result.angular()[2] += m1.wz();
229
230 return result;
231 }
232
233 template<typename Scalar, int Options>
234 struct JointMotionSubspacePlanarTpl;
235
236 template<typename _Scalar, int _Options>
238 {
239 typedef _Scalar Scalar;
240 enum
241 {
242 Options = _Options
243 };
244 enum
245 {
246 LINEAR = 0,
247 ANGULAR = 3
248 };
250 typedef Eigen::Matrix<Scalar, 3, 1, Options> JointForce;
251 typedef Eigen::Matrix<Scalar, 6, 3, Options> DenseBase;
252 typedef Eigen::Matrix<Scalar, 3, 3, Options> ReducedSquaredMatrix;
253
254 typedef DenseBase MatrixReturnType;
255 typedef const DenseBase ConstMatrixReturnType;
256
257 typedef typename ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType;
258 }; // struct traits JointMotionSubspacePlanarTpl
259
260 template<typename _Scalar, int _Options>
262 : JointMotionSubspaceBase<JointMotionSubspacePlanarTpl<_Scalar, _Options>>
263 {
265 PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(JointMotionSubspacePlanarTpl)
266
267 enum
268 {
269 NV = 3
270 };
271
273
274 template<typename Vector3Like>
275 JointMotion __mult__(const Eigen::MatrixBase<Vector3Like> & vj) const
276 {
278 return JointMotion(vj);
279 }
280
281 int nv_impl() const
282 {
283 return NV;
284 }
285
286 struct ConstraintTranspose : JointMotionSubspaceTransposeBase<JointMotionSubspacePlanarTpl>
287 {
290 : ref(ref)
291 {
292 }
293
294 template<typename Derived>
295 typename ForceDense<Derived>::Vector3 operator*(const ForceDense<Derived> & phi)
296 {
297 typedef typename ForceDense<Derived>::Vector3 Vector3;
298 return Vector3(phi.linear()[0], phi.linear()[1], phi.angular()[2]);
299 }
300
301 /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
302 template<typename Derived>
303 friend typename Eigen::
304 Matrix<typename Eigen::MatrixBase<Derived>::Scalar, 3, Derived::ColsAtCompileTime>
305 operator*(const ConstraintTranspose &, const Eigen::MatrixBase<Derived> & F)
306 {
307 typedef typename Eigen::MatrixBase<Derived>::Scalar Scalar;
308 typedef Eigen::Matrix<Scalar, 3, Derived::ColsAtCompileTime> MatrixReturnType;
309 assert(F.rows() == 6);
310
311 MatrixReturnType result(3, F.cols());
312 result.template topRows<2>() = F.template topRows<2>();
313 result.template bottomRows<1>() = F.template bottomRows<1>();
314 return result;
315 }
316
317 }; // struct ConstraintTranspose
318
319 ConstraintTranspose transpose() const
320 {
321 return ConstraintTranspose(*this);
322 }
323
324 DenseBase matrix_impl() const
325 {
326 DenseBase S;
327 S.template block<3, 3>(Inertia::LINEAR, 0).setZero();
328 S.template block<3, 3>(Inertia::ANGULAR, 0).setZero();
329 S(Inertia::LINEAR + 0, 0) = Scalar(1);
330 S(Inertia::LINEAR + 1, 1) = Scalar(1);
331 S(Inertia::ANGULAR + 2, 2) = Scalar(1);
332 return S;
333 }
334
335 template<typename S1, int O1>
336 DenseBase se3Action(const SE3Tpl<S1, O1> & m) const
337 {
338 DenseBase X_subspace;
339
340 // LINEAR
341 X_subspace.template block<3, 2>(Motion::LINEAR, 0) = m.rotation().template leftCols<2>();
342 X_subspace.template block<3, 1>(Motion::LINEAR, 2).noalias() =
343 m.translation().cross(m.rotation().template rightCols<1>());
344
345 // ANGULAR
346 X_subspace.template block<3, 2>(Motion::ANGULAR, 0).setZero();
347 X_subspace.template block<3, 1>(Motion::ANGULAR, 2) = m.rotation().template rightCols<1>();
348
349 return X_subspace;
350 }
351
352 template<typename S1, int O1>
353 DenseBase se3ActionInverse(const SE3Tpl<S1, O1> & m) const
354 {
355 DenseBase X_subspace;
356
357 // LINEAR
358 X_subspace.template block<3, 2>(Motion::LINEAR, 0) =
359 m.rotation().transpose().template leftCols<2>();
360 X_subspace.template block<3, 1>(Motion::ANGULAR, 2).noalias() =
361 m.rotation().transpose() * m.translation(); // tmp variable
362 X_subspace.template block<3, 1>(Motion::LINEAR, 2).noalias() =
363 -X_subspace.template block<3, 1>(Motion::ANGULAR, 2)
364 .cross(m.rotation().transpose().template rightCols<1>());
365
366 // ANGULAR
367 X_subspace.template block<3, 2>(Motion::ANGULAR, 0).setZero();
368 X_subspace.template block<3, 1>(Motion::ANGULAR, 2) =
369 m.rotation().transpose().template rightCols<1>();
370
371 return X_subspace;
372 }
373
374 template<typename MotionDerived>
375 DenseBase motionAction(const MotionDense<MotionDerived> & m) const
376 {
377 const typename MotionDerived::ConstLinearType v = m.linear();
378 const typename MotionDerived::ConstAngularType w = m.angular();
379 DenseBase res(DenseBase::Zero());
380
381 res(0, 1) = -w[2];
382 res(0, 2) = v[1];
383 res(1, 0) = w[2];
384 res(1, 2) = -v[0];
385 res(2, 0) = -w[1];
386 res(2, 1) = w[0];
387 res(3, 2) = w[1];
388 res(4, 2) = -w[0];
389
390 return res;
391 }
392
393 bool isEqual(const JointMotionSubspacePlanarTpl &) const
394 {
395 return true;
396 }
397
398 }; // struct JointMotionSubspacePlanarTpl
399
400 template<typename MotionDerived, typename S2, int O2>
401 inline typename MotionDerived::MotionPlain
402 operator^(const MotionDense<MotionDerived> & m1, const MotionPlanarTpl<S2, O2> & m2)
403 {
404 return m2.motionAction(m1);
405 }
406
407 /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
408 template<typename S1, int O1, typename S2, int O2>
409 inline typename Eigen::Matrix<S1, 6, 3, O1>
410 operator*(const InertiaTpl<S1, O1> & Y, const JointMotionSubspacePlanarTpl<S2, O2> &)
411 {
412 typedef InertiaTpl<S1, O1> Inertia;
413 typedef typename Inertia::Scalar Scalar;
414 typedef Eigen::Matrix<S1, 6, 3, O1> ReturnType;
415
416 ReturnType M;
417 const Scalar mass = Y.mass();
418 const typename Inertia::Vector3 & com = Y.lever();
419 const typename Inertia::Symmetric3 & inertia = Y.inertia();
420
421 M.template topLeftCorner<3, 3>().setZero();
422 M.template topLeftCorner<2, 2>().diagonal().fill(mass);
423
424 const typename Inertia::Vector3 mc(mass * com);
425 M.template rightCols<1>().template head<2>() << -mc(1), mc(0);
426
427 M.template bottomLeftCorner<3, 2>() << (Scalar)0, -mc(2), mc(2), (Scalar)0, -mc(1), mc(0);
428 M.template rightCols<1>().template tail<3>() = inertia.data().template tail<3>();
429 M.template rightCols<1>()[3] -= mc(0) * com(2);
430 M.template rightCols<1>()[4] -= mc(1) * com(2);
431 M.template rightCols<1>()[5] += mass * (com(0) * com(0) + com(1) * com(1));
432
433 return M;
434 }
435
436 /* [ABA] Y*S operator (Inertia Y,Constraint S) */
437 // inline Eigen::Matrix<context::Scalar,6,1>
438
439 template<typename M6Like, typename S2, int O2>
440 inline Eigen::Matrix<S2, 6, 3, O2>
441 operator*(const Eigen::MatrixBase<M6Like> & Y, const JointMotionSubspacePlanarTpl<S2, O2> &)
442 {
443 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like, 6, 6);
444 typedef Eigen::Matrix<S2, 6, 3, O2> Matrix63;
445
446 Matrix63 IS;
447 IS.template leftCols<2>() = Y.template leftCols<2>();
448 IS.template rightCols<1>() = Y.template rightCols<1>();
449
450 return IS;
451 }
452
453 template<typename S1, int O1>
455 {
456 typedef Eigen::Matrix<S1, 6, 3, O1> ReturnType;
457 };
458
459 template<typename S1, int O1, typename MotionDerived>
461 {
462 typedef Eigen::Matrix<S1, 6, 3, O1> ReturnType;
463 };
464
465 template<typename Scalar, int Options>
467
468 template<typename _Scalar, int _Options>
470 {
471 enum
472 {
473 NQ = 4,
474 NV = 3,
475 NVExtended = 3
476 };
477 enum
478 {
479 Options = _Options
480 };
481 typedef _Scalar Scalar;
488
489 // [ABA]
490 typedef Eigen::Matrix<Scalar, 6, NV, Options> U_t;
491 typedef Eigen::Matrix<Scalar, NV, NV, Options> D_t;
492 typedef Eigen::Matrix<Scalar, 6, NV, Options> UD_t;
493
494 typedef Eigen::Matrix<Scalar, NQ, 1, Options> ConfigVector_t;
495 typedef Eigen::Matrix<Scalar, NV, 1, Options> TangentVector_t;
496
497 typedef boost::mpl::false_ is_mimicable_t;
498
499 PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
500 };
501
502 template<typename _Scalar, int _Options>
508 template<typename _Scalar, int _Options>
514
515 template<typename _Scalar, int _Options>
516 struct JointDataPlanarTpl : public JointDataBase<JointDataPlanarTpl<_Scalar, _Options>>
517 {
520 PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived);
521 PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
522
523 ConfigVector_t joint_q;
524 TangentVector_t joint_v;
525
526 Constraint_t S;
527 Transformation_t M;
528 Motion_t v;
529 Bias_t c;
530
531 // [ABA] specific data
532 U_t U;
533 D_t Dinv;
534 UD_t UDinv;
535 D_t StU;
536
538 : joint_q(Scalar(0), Scalar(0), Scalar(1), Scalar(0))
539 , joint_v(TangentVector_t::Zero())
540 , M(Transformation_t::Identity())
541 , v(Motion_t::Vector3::Zero())
542 , U(U_t::Zero())
543 , Dinv(D_t::Zero())
544 , UDinv(UD_t::Zero())
545 , StU(D_t::Zero())
546 {
547 }
548
549 static std::string classname()
550 {
551 return std::string("JointDataPlanar");
552 }
553 std::string shortname() const
554 {
555 return classname();
556 }
557
558 }; // struct JointDataPlanarTpl
559
560 PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelPlanarTpl);
561 template<typename _Scalar, int _Options>
562 struct JointModelPlanarTpl : public JointModelBase<JointModelPlanarTpl<_Scalar, _Options>>
563 {
566 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
567
569 using Base::id;
570 using Base::idx_q;
571 using Base::idx_v;
572 using Base::idx_vExtended;
573 using Base::setIndexes;
574
575 JointDataDerived createData() const
576 {
577 return JointDataDerived();
578 }
579
580 const std::vector<bool> hasConfigurationLimit() const
581 {
582 return {true, true, false, false};
583 }
584
585 const std::vector<bool> hasConfigurationLimitInTangent() const
586 {
587 return {true, true, false};
588 }
589
590 template<typename ConfigVector>
591 inline void
592 forwardKinematics(Transformation_t & M, const Eigen::MatrixBase<ConfigVector> & q_joint) const
593 {
594 const Scalar &c_theta = q_joint(2), &s_theta = q_joint(3);
595
596 M.rotation().template topLeftCorner<2, 2>() << c_theta, -s_theta, s_theta, c_theta;
597 M.translation().template head<2>() = q_joint.template head<2>();
598 }
599
600 template<typename ConfigVector>
601 void calc(JointDataDerived & data, const typename Eigen::MatrixBase<ConfigVector> & qs) const
602 {
603 data.joint_q = qs.template segment<NQ>(idx_q());
604
605 const Scalar &c_theta = data.joint_q(2), &s_theta = data.joint_q(3);
606
607 data.M.rotation().template topLeftCorner<2, 2>() << c_theta, -s_theta, s_theta, c_theta;
608 data.M.translation().template head<2>() = data.joint_q.template head<2>();
609 }
610
611 template<typename TangentVector>
612 void
613 calc(JointDataDerived & data, const Blank, const typename Eigen::MatrixBase<TangentVector> & vs)
614 const
615 {
616 data.joint_v = vs.template segment<NV>(idx_v());
617
618#define q_dot data.joint_v
619 data.v.vx() = q_dot(0);
620 data.v.vy() = q_dot(1);
621 data.v.wz() = q_dot(2);
622#undef q_dot
623 }
624
625 template<typename ConfigVector, typename TangentVector>
626 void calc(
627 JointDataDerived & data,
628 const typename Eigen::MatrixBase<ConfigVector> & qs,
629 const typename Eigen::MatrixBase<TangentVector> & vs) const
630 {
631 calc(data, qs.derived());
632
633 data.joint_v = vs.template segment<NV>(idx_v());
634
635#define q_dot data.joint_v
636 data.v.vx() = q_dot(0);
637 data.v.vy() = q_dot(1);
638 data.v.wz() = q_dot(2);
639#undef q_dot
640 }
641
642 template<typename VectorLike, typename Matrix6Like>
643 void calc_aba(
644 JointDataDerived & data,
645 const Eigen::MatrixBase<VectorLike> & armature,
646 const Eigen::MatrixBase<Matrix6Like> & I,
647 const bool update_I) const
648 {
649 data.U.template leftCols<2>() = I.template leftCols<2>();
650 data.U.template rightCols<1>() = I.template rightCols<1>();
651
652 data.StU.template leftCols<2>() = data.U.template topRows<2>().transpose();
653 data.StU.template rightCols<1>() = data.U.template bottomRows<1>();
654
655 data.StU.diagonal() += armature;
656 internal::PerformStYSInversion<Scalar>::run(data.StU, data.Dinv);
657
658 data.UDinv.noalias() = data.U * data.Dinv;
659
660 if (update_I)
661 PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose();
662 }
663
664 static std::string classname()
665 {
666 return std::string("JointModelPlanar");
667 }
668 std::string shortname() const
669 {
670 return classname();
671 }
672
674 template<typename NewScalar>
676 {
678 ReturnType res;
679 res.setIndexes(id(), idx_q(), idx_v(), idx_vExtended());
680 return res;
681 }
682
683 }; // struct JointModelPlanarTpl
684
685 template<typename Scalar, int Options>
687 {
689 };
690} // namespace pinocchio
691
692#include <boost/type_traits.hpp>
693
694namespace boost
695{
696 template<typename Scalar, int Options>
697 struct has_nothrow_constructor<::pinocchio::JointModelPlanarTpl<Scalar, Options>>
698 : public integral_constant<bool, true>
699 {
700 };
701
702 template<typename Scalar, int Options>
703 struct has_nothrow_copy<::pinocchio::JointModelPlanarTpl<Scalar, Options>>
704 : public integral_constant<bool, true>
705 {
706 };
707
708 template<typename Scalar, int Options>
709 struct has_nothrow_constructor<::pinocchio::JointDataPlanarTpl<Scalar, Options>>
710 : public integral_constant<bool, true>
711 {
712 };
713
714 template<typename Scalar, int Options>
715 struct has_nothrow_copy<::pinocchio::JointDataPlanarTpl<Scalar, Options>>
716 : public integral_constant<bool, true>
717 {
718 };
719} // namespace boost
720
721#endif // ifndef __pinocchio_multibody_joint_planar_hpp__
Main pinocchio namespace.
Definition treeview.dox:11
JointDataTpl< Scalar, Options, JointCollectionTpl >::TangentVector_t joint_v(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConfigVisitor to get the joint velocity vector.
JointDataTpl< Scalar, Options, JointCollectionTpl >::ConfigVector_t joint_q(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConfigVisitor to get the joint configuration vector.
Blank type.
Definition fwd.hpp:77
Assign the correct configuration vector space affine transformation according to the joint type....
JointModelPlanarTpl< NewScalar, Options > cast() const
Linear affine transformation of the configuration vector. Valide for most common joints which are evo...
Return type of the ation of a Motion onto an object of type D.
Definition motion.hpp:46
Common traits structure to fully define base classes for CRTP.
Definition fwd.hpp:72