joint-prismatic-unaligned.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 // Copyright (c) 2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_multibody_joint_prismatic_unaligned_hpp__
7 #define __pinocchio_multibody_joint_prismatic_unaligned_hpp__
8 
9 #include "pinocchio/macros.hpp"
15 
16 namespace pinocchio
17 {
18 
19  template<typename Scalar, int Options = context::Options>
22 
23  template<typename Scalar, int Options>
25  {
27  };
28 
29  template<typename Scalar, int Options, typename MotionDerived>
31  {
33  };
34 
35  template<typename _Scalar, int _Options>
36  struct traits<MotionPrismaticUnalignedTpl<_Scalar, _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;
51  typedef const Vector3 ConstAngularType;
52  typedef const Vector3 ConstLinearType;
57  enum
58  {
59  LINEAR = 0,
60  ANGULAR = 3
61  };
62  }; // traits MotionPrismaticUnalignedTpl
63 
64  template<typename _Scalar, int _Options>
65  struct MotionPrismaticUnalignedTpl : MotionBase<MotionPrismaticUnalignedTpl<_Scalar, _Options>>
66  {
67  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
69 
71  {
72  }
73 
74  template<typename Vector3Like, typename S2>
75  MotionPrismaticUnalignedTpl(const Eigen::MatrixBase<Vector3Like> & axis, const S2 & v)
76  : m_axis(axis)
77  , m_v(v)
78  {
79  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
80  }
81 
82  inline PlainReturnType plain() const
83  {
84  return PlainReturnType(m_axis * m_v, PlainReturnType::Vector3::Zero());
85  }
86 
87  template<typename OtherScalar>
88  MotionPrismaticUnalignedTpl __mult__(const OtherScalar & alpha) const
89  {
91  }
92 
93  template<typename Derived>
94  void addTo(MotionDense<Derived> & other) const
95  {
96  other.linear() += m_axis * m_v;
97  }
98 
99  template<typename Derived>
100  void setTo(MotionDense<Derived> & other) const
101  {
102  other.linear().noalias() = m_axis * m_v;
103  other.angular().setZero();
104  }
105 
106  template<typename S2, int O2, typename D2>
108  {
109  v.linear().noalias() = m_v * (m.rotation() * m_axis); // TODO: check efficiency
110  v.angular().setZero();
111  }
112 
113  template<typename S2, int O2>
114  MotionPlain se3Action_impl(const SE3Tpl<S2, O2> & m) const
115  {
116  MotionPlain res;
117  se3Action_impl(m, res);
118  return res;
119  }
120 
121  template<typename S2, int O2, typename D2>
123  {
124  // Linear
125  v.linear().noalias() = m_v * (m.rotation().transpose() * m_axis);
126 
127  // Angular
128  v.angular().setZero();
129  }
130 
131  template<typename S2, int O2>
132  MotionPlain se3ActionInverse_impl(const SE3Tpl<S2, O2> & m) const
133  {
134  MotionPlain res;
136  return res;
137  }
138 
139  template<typename M1, typename M2>
140  void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
141  {
142  // Linear
143  mout.linear().noalias() = v.angular().cross(m_axis);
144  mout.linear() *= m_v;
145 
146  // Angular
147  mout.angular().setZero();
148  }
149 
150  template<typename M1>
151  MotionPlain motionAction(const MotionDense<M1> & v) const
152  {
153  MotionPlain res;
154  motionAction(v, res);
155  return res;
156  }
157 
158  bool isEqual_impl(const MotionPrismaticUnalignedTpl & other) const
159  {
160  return internal::comparison_eq(m_axis, other.m_axis)
161  && internal::comparison_eq(m_v, other.m_v);
162  }
163 
164  const Scalar & linearRate() const
165  {
166  return m_v;
167  }
169  {
170  return m_v;
171  }
172 
173  const Vector3 & axis() const
174  {
175  return m_axis;
176  }
178  {
179  return m_axis;
180  }
181 
182  protected:
185  }; // struct MotionPrismaticUnalignedTpl
186 
187  template<typename Scalar, int Options, typename MotionDerived>
188  inline typename MotionDerived::MotionPlain operator+(
190  {
191  typedef typename MotionDerived::MotionPlain ReturnType;
192  return ReturnType(m1.linearRate() * m1.axis() + m2.linear(), m2.angular());
193  }
194 
195  template<typename MotionDerived, typename S2, int O2>
196  inline typename MotionDerived::MotionPlain
198  {
199  return m2.motionAction(m1);
200  }
201 
202  template<typename Scalar, int Options>
204 
205  template<typename _Scalar, int _Options>
207  {
208  typedef _Scalar Scalar;
209  enum
210  {
211  Options = _Options
212  };
213  enum
214  {
215  LINEAR = 0,
216  ANGULAR = 3
217  };
218 
220  typedef Eigen::Matrix<Scalar, 1, 1, Options> JointForce;
221  typedef Eigen::Matrix<Scalar, 6, 1, Options> DenseBase;
222  typedef Eigen::Matrix<Scalar, 1, 1, Options> ReducedSquaredMatrix;
223  typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
224 
227 
228  typedef typename ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType;
229  }; // traits JointMotionSubspacePrismaticUnalignedTpl
230 
231  template<typename Scalar, int Options>
233  {
234  typedef Eigen::Matrix<Scalar, 6, 1, Options> ReturnType;
235  };
236 
237  template<typename Scalar, int Options, typename MotionDerived>
240  MotionDerived>
241  {
242  typedef Eigen::Matrix<Scalar, 6, 1, Options> ReturnType;
243  };
244 
245  template<typename Scalar, int Options, typename ForceDerived>
247  {
248  typedef
250  typedef Eigen::Matrix<
253  1,
254  1,
255  Options>
257  };
258 
259  template<typename Scalar, int Options, typename ForceSet>
261  {
262  typedef
264  typedef typename MatrixMatrixProduct<
265  Eigen::Transpose<const Vector3>,
266  typename Eigen::MatrixBase<const ForceSet>::template NRowsBlockXpr<3>::Type>::type ReturnType;
267  };
268 
269  template<typename _Scalar, int _Options>
271  : JointMotionSubspaceBase<JointMotionSubspacePrismaticUnalignedTpl<_Scalar, _Options>>
272  {
273  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
275 
276  enum
277  {
278  NV = 1
279  };
280 
282 
284  {
285  }
286 
287  template<typename Vector3Like>
288  JointMotionSubspacePrismaticUnalignedTpl(const Eigen::MatrixBase<Vector3Like> & axis)
289  : m_axis(axis)
290  {
291  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
292  }
293 
294  template<typename Vector1Like>
295  JointMotion __mult__(const Eigen::MatrixBase<Vector1Like> & v) const
296  {
297  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like, 1);
298  return JointMotion(m_axis, v[0]);
299  }
300 
301  template<typename S1, int O1>
303  se3Action(const SE3Tpl<S1, O1> & m) const
304  {
307  v.linear().noalias() = m.rotation() * m_axis;
308  v.angular().setZero();
309  return res;
310  }
311 
312  template<typename S1, int O1>
315  {
318  v.linear().noalias() = m.rotation().transpose() * m_axis;
319  v.angular().setZero();
320  return res;
321  }
322 
323  int nv_impl() const
324  {
325  return NV;
326  }
327 
329  : JointMotionSubspaceTransposeBase<JointMotionSubspacePrismaticUnalignedTpl>
330  {
333  : ref(ref)
334  {
335  }
336 
337  template<typename ForceDerived>
340  {
341  typedef typename ConstraintForceOp<
342  JointMotionSubspacePrismaticUnalignedTpl, ForceDerived>::ReturnType ReturnType;
343  ReturnType res;
344  res[0] = ref.axis().dot(f.linear());
345  return res;
346  }
347 
348  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
349  template<typename ForceSet>
351  operator*(const Eigen::MatrixBase<ForceSet> & F)
352  {
353  EIGEN_STATIC_ASSERT(
354  ForceSet::RowsAtCompileTime == 6, THIS_METHOD_IS_ONLY_FOR_MATRICES_OF_A_SPECIFIC_SIZE)
355  /* Return ax.T * F[1:3,:] */
356  return ref.axis().transpose() * F.template middleRows<3>(LINEAR);
357  }
358  };
359 
361  {
362  return TransposeConst(*this);
363  }
364 
365  /* CRBA joint operators
366  * - ForceSet::Block = ForceSet
367  * - ForceSet operator* (Inertia Y,Constraint S)
368  * - MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)
369  * - SE3::act(ForceSet::Block)
370  */
371  DenseBase matrix_impl() const
372  {
373  DenseBase S;
374  S.template segment<3>(LINEAR) = m_axis;
375  S.template segment<3>(ANGULAR).setZero();
376  return S;
377  }
378 
379  template<typename MotionDerived>
380  DenseBase motionAction(const MotionDense<MotionDerived> & v) const
381  {
382  DenseBase res;
383  res.template segment<3>(LINEAR).noalias() = v.angular().cross(m_axis);
384  res.template segment<3>(ANGULAR).setZero();
385 
386  return res;
387  }
388 
389  const Vector3 & axis() const
390  {
391  return m_axis;
392  }
394  {
395  return m_axis;
396  }
397 
399  {
400  return internal::comparison_eq(m_axis, other.m_axis);
401  }
402 
403  protected:
405 
406  }; // struct JointMotionSubspacePrismaticUnalignedTpl
407 
408  template<typename S1, int O1, typename S2, int O2>
410  {
411  typedef Eigen::Matrix<S2, 6, 1, O2> ReturnType;
412  };
413 
414  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
415  namespace impl
416  {
417  template<typename S1, int O1, typename S2, int O2>
419  {
423 
424  static inline ReturnType run(const Inertia & Y, const Constraint & cpu)
425  {
426  ReturnType res;
427  /* YS = [ m -mcx ; mcx I-mcxcx ] [ 0 ; w ] = [ mcxw ; Iw -mcxcxw ] */
428  const S1 & m = Y.mass();
429  const typename Inertia::Vector3 & c = Y.lever();
430 
431  res.template segment<3>(Constraint::LINEAR).noalias() = m * cpu.axis();
432  res.template segment<3>(Constraint::ANGULAR).noalias() =
433  c.cross(res.template segment<3>(Constraint::LINEAR));
434 
435  return res;
436  }
437  };
438  } // namespace impl
439 
440  template<typename M6Like, typename Scalar, int Options>
442  Eigen::MatrixBase<M6Like>,
444  {
445  typedef typename SizeDepType<3>::ColsReturn<M6Like>::ConstType M6LikeCols;
447 
449  typedef typename Constraint::Vector3 Vector3;
451  };
452 
453  /* [ABA] operator* (Inertia Y,Constraint S) */
454  namespace impl
455  {
456  template<typename M6Like, typename Scalar, int Options>
458  Eigen::MatrixBase<M6Like>,
460  {
462  typedef
464  static inline ReturnType run(const Eigen::MatrixBase<M6Like> & Y, const Constraint & cru)
465  {
466  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like, 6, 6);
467  return Y.derived().template middleCols<3>(Constraint::LINEAR) * cru.axis();
468  }
469  };
470  } // namespace impl
471 
472  template<typename Scalar, int Options>
474 
475  template<typename _Scalar, int _Options>
476  struct traits<JointPrismaticUnalignedTpl<_Scalar, _Options>>
477  {
478  enum
479  {
480  NQ = 1,
481  NV = 1
482  };
483  typedef _Scalar Scalar;
484  enum
485  {
486  Options = _Options
487  };
494 
495  // [ABA]
496  typedef Eigen::Matrix<Scalar, 6, NV, Options> U_t;
497  typedef Eigen::Matrix<Scalar, NV, NV, Options> D_t;
498  typedef Eigen::Matrix<Scalar, 6, NV, Options> UD_t;
499 
500  typedef Eigen::Matrix<Scalar, NQ, 1, Options> ConfigVector_t;
501  typedef Eigen::Matrix<Scalar, NV, 1, Options> TangentVector_t;
502 
504  };
505 
506  template<typename _Scalar, int _Options>
507  struct traits<JointDataPrismaticUnalignedTpl<_Scalar, _Options>>
508  {
510  typedef _Scalar Scalar;
511  };
512 
513  template<typename _Scalar, int _Options>
515  : public JointDataBase<JointDataPrismaticUnalignedTpl<_Scalar, _Options>>
516  {
517  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
521 
522  ConfigVector_t joint_q;
523  TangentVector_t joint_v;
524 
525  Transformation_t M;
526  Constraint_t S;
527  Motion_t v;
528  Bias_t c;
529 
530  // [ABA] specific data
531  U_t U;
532  D_t Dinv;
533  UD_t UDinv;
534  D_t StU;
535 
537  : joint_q(ConfigVector_t::Zero())
538  , joint_v(TangentVector_t::Zero())
539  , M(Transformation_t::Vector3::Zero())
540  , S(Constraint_t::Vector3::Zero())
541  , v(Constraint_t::Vector3::Zero(), (Scalar)0)
542  , U(U_t::Zero())
543  , Dinv(D_t::Zero())
544  , UDinv(UD_t::Zero())
545  , StU(D_t::Zero())
546  {
547  }
548 
549  template<typename Vector3Like>
550  JointDataPrismaticUnalignedTpl(const Eigen::MatrixBase<Vector3Like> & axis)
551  : joint_q(ConfigVector_t::Zero())
552  , joint_v(TangentVector_t::Zero())
553  , M(Transformation_t::Vector3::Zero())
554  , S(axis)
555  , v(axis, (Scalar)0)
556  , U(U_t::Zero())
557  , Dinv(D_t::Zero())
558  , UDinv(UD_t::Zero())
559  , StU(D_t::Zero())
560  {
561  }
562 
563  static std::string classname()
564  {
565  return std::string("JointDataPrismaticUnaligned");
566  }
567  std::string shortname() const
568  {
569  return classname();
570  }
571 
572  }; // struct JointDataPrismaticUnalignedTpl
573 
574  template<typename _Scalar, int _Options>
575  struct traits<JointModelPrismaticUnalignedTpl<_Scalar, _Options>>
576  {
578  typedef _Scalar Scalar;
579  };
580 
582  template<typename _Scalar, int _Options>
584  : public JointModelBase<JointModelPrismaticUnalignedTpl<_Scalar, _Options>>
585  {
586  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
589 
591  using Base::id;
592  using Base::idx_q;
593  using Base::idx_v;
594  using Base::setIndexes;
595 
596  typedef Eigen::Matrix<Scalar, 3, 1, _Options> Vector3;
597 
599  : axis(Vector3::UnitX())
600  {
601  }
602  JointModelPrismaticUnalignedTpl(const Scalar & x, const Scalar & y, const Scalar & z)
603  : axis(x, y, z)
604  {
605  normalize(axis);
606  assert(isUnitary(axis) && "Translation axis is not unitary");
607  }
608 
609  template<typename Vector3Like>
610  JointModelPrismaticUnalignedTpl(const Eigen::MatrixBase<Vector3Like> & axis)
611  : axis(axis)
612  {
613  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Vector3Like);
614  assert(isUnitary(axis) && "Translation axis is not unitary");
615  }
616 
617  JointDataDerived createData() const
618  {
619  return JointDataDerived(axis);
620  }
621 
622  const std::vector<bool> hasConfigurationLimit() const
623  {
624  return {true};
625  }
626 
627  const std::vector<bool> hasConfigurationLimitInTangent() const
628  {
629  return {true};
630  }
631 
632  using Base::isEqual;
633  bool isEqual(const JointModelPrismaticUnalignedTpl & other) const
634  {
635  return Base::isEqual(other) && internal::comparison_eq(axis, other.axis);
636  }
637 
638  template<typename ConfigVector>
639  void calc(JointDataDerived & data, const typename Eigen::MatrixBase<ConfigVector> & qs) const
640  {
641  data.joint_q[0] = qs[idx_q()];
642  data.M.translation().noalias() = axis * data.joint_q[0];
643  }
644 
645  template<typename TangentVector>
646  void
647  calc(JointDataDerived & data, const Blank, const typename Eigen::MatrixBase<TangentVector> & vs)
648  const
649  {
650  data.joint_v[0] = vs[idx_v()];
651  data.v.linearRate() = data.joint_v[0];
652  }
653 
654  template<typename ConfigVector, typename TangentVector>
655  void calc(
656  JointDataDerived & data,
657  const typename Eigen::MatrixBase<ConfigVector> & qs,
658  const typename Eigen::MatrixBase<TangentVector> & vs) const
659  {
660  calc(data, qs.derived());
661 
662  data.joint_v[0] = vs[idx_v()];
663  data.v.linearRate() = data.joint_v[0];
664  }
665 
666  template<typename VectorLike, typename Matrix6Like>
667  void calc_aba(
668  JointDataDerived & data,
669  const Eigen::MatrixBase<VectorLike> & armature,
670  const Eigen::MatrixBase<Matrix6Like> & I,
671  const bool update_I) const
672  {
673  data.U.noalias() = I.template block<6, 3>(0, Inertia::LINEAR) * axis;
674  data.Dinv[0] =
675  Scalar(1) / (axis.dot(data.U.template segment<3>(Inertia::LINEAR)) + armature[0]);
676  data.UDinv.noalias() = data.U * data.Dinv;
677 
678  if (update_I)
679  PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose();
680  }
681 
682  static std::string classname()
683  {
684  return std::string("JointModelPrismaticUnaligned");
685  }
686  std::string shortname() const
687  {
688  return classname();
689  }
690 
692  template<typename NewScalar>
694  {
696  ReturnType res(axis.template cast<NewScalar>());
697  res.setIndexes(id(), idx_q(), idx_v());
698  return res;
699  }
700 
701  // data
702 
707  }; // struct JointModelPrismaticUnalignedTpl
708 
709 } // namespace pinocchio
710 
711 #include <boost/type_traits.hpp>
712 
713 namespace boost
714 {
715  template<typename Scalar, int Options>
716  struct has_nothrow_constructor<::pinocchio::JointModelPrismaticUnalignedTpl<Scalar, Options>>
717  : public integral_constant<bool, true>
718  {
719  };
720 
721  template<typename Scalar, int Options>
722  struct has_nothrow_copy<::pinocchio::JointModelPrismaticUnalignedTpl<Scalar, Options>>
723  : public integral_constant<bool, true>
724  {
725  };
726 
727  template<typename Scalar, int Options>
728  struct has_nothrow_constructor<::pinocchio::JointDataPrismaticUnalignedTpl<Scalar, Options>>
729  : public integral_constant<bool, true>
730  {
731  };
732 
733  template<typename Scalar, int Options>
734  struct has_nothrow_copy<::pinocchio::JointDataPrismaticUnalignedTpl<Scalar, Options>>
735  : public integral_constant<bool, true>
736  {
737  };
738 } // namespace boost
739 
740 #endif // ifndef __pinocchio_multibody_joint_prismatic_unaligned_hpp__
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::TransposeConst::operator*
ConstraintForceOp< JointMotionSubspacePrismaticUnalignedTpl, ForceDerived >::ReturnType operator*(const ForceDense< ForceDerived > &f) const
Definition: joint-prismatic-unaligned.hpp:339
pinocchio::JointModelPrismaticUnalignedTpl::JointDerived
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
Definition: joint-prismatic-unaligned.hpp:587
pinocchio::InertiaTpl
Definition: spatial/fwd.hpp:58
pinocchio::JointDataPrismaticUnalignedTpl::joint_q
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
Definition: joint-prismatic-unaligned.hpp:522
pinocchio::MatrixMatrixProduct
Definition: math/matrix.hpp:68
pinocchio::MotionPrismaticUnalignedTpl
Definition: joint-prismatic-unaligned.hpp:20
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::JointMotionSubspacePrismaticUnalignedTpl
JointMotionSubspacePrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
Definition: joint-prismatic-unaligned.hpp:288
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::Matrix6
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
Definition: joint-prismatic-unaligned.hpp:46
pinocchio::JointModelPrismaticUnalignedTpl::calc
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
Definition: joint-prismatic-unaligned.hpp:639
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
Definition: joint-data-base.hpp:137
UnitX
const Vec3f UnitX
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::TransposeConst::operator*
ConstraintForceSetOp< JointMotionSubspacePrismaticUnalignedTpl, ForceSet >::ReturnType operator*(const Eigen::MatrixBase< ForceSet > &F)
Definition: joint-prismatic-unaligned.hpp:351
Eigen
pinocchio::MultiplicationOp
Forward declaration of the multiplication operation return type. Should be overloaded,...
Definition: binary-op.hpp:15
test-cpp2pybind11.m
m
Definition: test-cpp2pybind11.py:22
pinocchio::MultiplicationOp< Eigen::MatrixBase< M6Like >, JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::ReturnType
const typedef MatrixMatrixProduct< M6LikeColsNonConst, Vector3 >::type ReturnType
Definition: joint-prismatic-unaligned.hpp:450
pinocchio::SE3GroupAction< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::ReturnType
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
Definition: joint-prismatic-unaligned.hpp:234
pinocchio::JointModelPrismaticUnalignedTpl::shortname
std::string shortname() const
Definition: joint-prismatic-unaligned.hpp:686
PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE
#define PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE(D1, D2)
Macro giving access to the return type of the dot product operation.
Definition: eigen-macros.hpp:44
pinocchio::ConstraintForceOp< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options >, ForceDerived >::ReturnType
Eigen::Matrix< typename PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE(Vector3, typename ForceDense< ForceDerived >::ConstAngularType), 1, 1, Options > ReturnType
Definition: joint-prismatic-unaligned.hpp:256
pinocchio::JointModelPrismaticUnalignedTpl::JointModelPrismaticUnalignedTpl
JointModelPrismaticUnalignedTpl()
Definition: joint-prismatic-unaligned.hpp:598
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::ReducedSquaredMatrix
Eigen::Matrix< Scalar, 1, 1, Options > ReducedSquaredMatrix
Definition: joint-prismatic-unaligned.hpp:222
pinocchio::MotionPrismaticUnalignedTpl::motionAction
MotionPlain motionAction(const MotionDense< M1 > &v) const
Definition: joint-prismatic-unaligned.hpp:151
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::m_axis
Vector3 m_axis
Definition: joint-prismatic-unaligned.hpp:404
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::UD_t
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
Definition: joint-prismatic-unaligned.hpp:498
macros.hpp
pinocchio::JointDataPrismaticUnalignedTpl::shortname
std::string shortname() const
Definition: joint-prismatic-unaligned.hpp:567
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::Scalar
_Scalar Scalar
Definition: joint-prismatic-unaligned.hpp:38
pinocchio::isUnitary
bool isUnitary(const Eigen::MatrixBase< MatrixLike > &mat, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
Check whether the input matrix is Unitary within the given precision.
Definition: math/matrix.hpp:155
pinocchio::idx_q
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
pinocchio::ConstraintForceOp< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options >, ForceDerived >::Vector3
traits< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::Vector3 Vector3
Definition: joint-prismatic-unaligned.hpp:249
pinocchio::MotionPrismaticUnalignedTpl::m_axis
Vector3 m_axis
Definition: joint-prismatic-unaligned.hpp:183
pinocchio::JointModelBase
Definition: joint-model-base.hpp:75
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::se3ActionInverse
SE3GroupAction< JointMotionSubspacePrismaticUnalignedTpl >::ReturnType se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
Definition: joint-prismatic-unaligned.hpp:314
pinocchio::impl::LhsMultiplicationOp< Eigen::MatrixBase< M6Like >, JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::Constraint
JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > Constraint
Definition: joint-prismatic-unaligned.hpp:461
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::LinearType
Vector3 LinearType
Definition: joint-prismatic-unaligned.hpp:50
pinocchio::JointModelPrismaticUnalignedTpl::hasConfigurationLimitInTangent
const std::vector< bool > hasConfigurationLimitInTangent() const
Definition: joint-prismatic-unaligned.hpp:627
pinocchio::ConstraintForceOp
Return type of the Constraint::Transpose * Force operation.
Definition: constraint-base.hpp:46
pinocchio::idx_v
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxVVisitor to get the index in the full model tangent space corre...
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
pinocchio::MotionPrismaticUnalignedTpl::linearRate
Scalar & linearRate()
Definition: joint-prismatic-unaligned.hpp:168
y
y
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: joint-prismatic-unaligned.hpp:223
pinocchio::traits< JointDataPrismaticUnalignedTpl< _Scalar, _Options > >::Scalar
_Scalar Scalar
Definition: joint-prismatic-unaligned.hpp:510
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::MatrixReturnType
DenseBase MatrixReturnType
Definition: joint-prismatic-unaligned.hpp:225
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::isEqual
bool isEqual(const JointMotionSubspacePrismaticUnalignedTpl &other) const
Definition: joint-prismatic-unaligned.hpp:398
pinocchio::JointMotionSubspaceBase
Definition: constraint-base.hpp:59
c
Vec3f c
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::JointMotion
MotionPrismaticUnalignedTpl< Scalar, Options > JointMotion
Definition: joint-prismatic-unaligned.hpp:219
PINOCCHIO_EIGEN_CONST_CAST
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Definition: eigen-macros.hpp:51
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
pinocchio::JointModelPrismaticUnalignedTpl::JointModelPrismaticUnalignedTpl
JointModelPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
Definition: joint-prismatic-unaligned.hpp:610
pinocchio::SE3GroupAction::ReturnType
D ReturnType
Definition: spatial/se3.hpp:41
pinocchio::JointPrismaticUnalignedTpl
Definition: joint-prismatic-unaligned.hpp:473
pinocchio::JointDataBase
Definition: joint-data-base.hpp:161
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::ConstMatrixReturnType
const typedef DenseBase ConstMatrixReturnType
Definition: joint-prismatic-unaligned.hpp:226
pinocchio::PINOCCHIO_EIGEN_REF_CONST_TYPE
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
Definition: joint-free-flyer.hpp:144
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::nv_impl
int nv_impl() const
Definition: joint-prismatic-unaligned.hpp:323
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::NV
@ NV
Definition: joint-prismatic-unaligned.hpp:278
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::JointDataPrismaticUnalignedTpl::Dinv
D_t Dinv
Definition: joint-prismatic-unaligned.hpp:532
inertia.hpp
pinocchio::impl::LhsMultiplicationOp< Eigen::MatrixBase< M6Like >, JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::ReturnType
MultiplicationOp< Eigen::MatrixBase< M6Like >, Constraint >::ReturnType ReturnType
Definition: joint-prismatic-unaligned.hpp:463
pinocchio::MotionDense
Definition: context/casadi.hpp:36
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::JointModelPrismaticUnalignedTpl::JointModelPrismaticUnalignedTpl
JointModelPrismaticUnalignedTpl(const Scalar &x, const Scalar &y, const Scalar &z)
Definition: joint-prismatic-unaligned.hpp:602
pinocchio::MotionPrismaticUnalignedTpl::axis
const Vector3 & axis() const
Definition: joint-prismatic-unaligned.hpp:173
pinocchio::operator+
MotionDerived::MotionPlain operator+(const MotionHelicalUnalignedTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2)
Definition: joint-helical-unaligned.hpp:213
boost
pinocchio::ConstraintForceOp::ReturnType
ReturnTypeNotDefined ReturnType
Definition: constraint-base.hpp:48
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::TangentVector_t
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
Definition: joint-prismatic-unaligned.hpp:501
pinocchio::JointModelBase::setIndexes
void setIndexes(JointIndex id, int q, int v)
Definition: joint-model-base.hpp:186
pinocchio::JointDataPrismaticUnalignedTpl::StU
D_t StU
Definition: joint-prismatic-unaligned.hpp:534
pinocchio::MotionPrismaticUnalignedTpl::linearRate
const Scalar & linearRate() const
Definition: joint-prismatic-unaligned.hpp:164
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
pinocchio::MotionPrismaticUnalignedTpl::MotionPrismaticUnalignedTpl
MotionPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis, const S2 &v)
Definition: joint-prismatic-unaligned.hpp:75
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::JointForce
Eigen::Matrix< Scalar, 1, 1, Options > JointForce
Definition: joint-prismatic-unaligned.hpp:220
pinocchio::MultiplicationOp< Eigen::MatrixBase< M6Like >, JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::Constraint
JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > Constraint
Definition: joint-prismatic-unaligned.hpp:448
pinocchio::JointModelPrismaticUnalignedTpl::hasConfigurationLimit
const std::vector< bool > hasConfigurationLimit() const
Definition: joint-prismatic-unaligned.hpp:622
pinocchio::MotionAlgebraAction
Return type of the ation of a Motion onto an object of type D.
Definition: spatial/motion.hpp:45
pinocchio::MotionPrismaticUnalignedTpl::addTo
void addTo(MotionDense< Derived > &other) const
Definition: joint-prismatic-unaligned.hpp:94
pinocchio::impl::LhsMultiplicationOp
Definition: binary-op.hpp:20
autodiff-rnea.f
f
Definition: autodiff-rnea.py:24
pinocchio::MotionPrismaticUnalignedTpl::__mult__
MotionPrismaticUnalignedTpl __mult__(const OtherScalar &alpha) const
Definition: joint-prismatic-unaligned.hpp:88
pinocchio::Blank
Blank type.
Definition: fwd.hpp:76
pinocchio::MotionPrismaticUnalignedTpl::plain
PlainReturnType plain() const
Definition: joint-prismatic-unaligned.hpp:82
pinocchio::JointDataPrismaticUnalignedTpl::JointDerived
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
Definition: joint-prismatic-unaligned.hpp:518
pinocchio::MotionPrismaticUnalignedTpl::setTo
void setTo(MotionDense< Derived > &other) const
Definition: joint-prismatic-unaligned.hpp:100
pinocchio::MotionAlgebraAction< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options >, MotionDerived >::ReturnType
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
Definition: joint-prismatic-unaligned.hpp:242
pinocchio::MotionDense::linear
ConstLinearType linear() const
Definition: motion-base.hpp:36
pinocchio::SE3GroupAction
Definition: spatial/se3.hpp:39
pinocchio::JointModelPrismaticUnalignedTpl::calc
void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
Definition: joint-prismatic-unaligned.hpp:647
pinocchio::JointModelPrismaticUnalignedTpl::classname
static std::string classname()
Definition: joint-prismatic-unaligned.hpp:682
pinocchio::MotionZeroTpl
Definition: context/casadi.hpp:23
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
Definition: joint-data-base.hpp:55
simulation-pendulum.type
type
Definition: simulation-pendulum.py:18
pinocchio::JointMotionSubspacePrismaticUnalignedTpl
Definition: joint-prismatic-unaligned.hpp:203
pinocchio::MotionPrismaticUnalignedTpl::MotionPrismaticUnalignedTpl
MotionPrismaticUnalignedTpl()
Definition: joint-prismatic-unaligned.hpp:70
pinocchio::traits< JointModelPrismaticUnalignedTpl< _Scalar, _Options > >::JointDerived
JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
Definition: joint-prismatic-unaligned.hpp:577
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::Transformation_t
TransformTranslationTpl< Scalar, Options > Transformation_t
Definition: joint-prismatic-unaligned.hpp:491
pinocchio::MotionPrismaticUnalignedTpl::se3Action_impl
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
Definition: joint-prismatic-unaligned.hpp:114
pinocchio::MotionPrismaticUnalignedTpl::m_v
Scalar m_v
Definition: joint-prismatic-unaligned.hpp:184
pinocchio::ConstraintForceSetOp::ReturnType
ReturnTypeNotDefined ReturnType
Definition: constraint-base.hpp:55
simulation-contact-dynamics.S
S
Definition: simulation-contact-dynamics.py:85
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::se3Action
SE3GroupAction< JointMotionSubspacePrismaticUnalignedTpl >::ReturnType se3Action(const SE3Tpl< S1, O1 > &m) const
Definition: joint-prismatic-unaligned.hpp:303
matrix.hpp
reachable-workspace-with-collisions.alpha
float alpha
Definition: reachable-workspace-with-collisions.py:159
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::JointDataDerived
JointDataPrismaticUnalignedTpl< Scalar, Options > JointDataDerived
Definition: joint-prismatic-unaligned.hpp:488
joint-translation.hpp
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::DenseBase
Eigen::Matrix< Scalar, 6, 1, Options > DenseBase
Definition: joint-prismatic-unaligned.hpp:221
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
pinocchio::JointDataPrismaticUnalignedTpl::S
Constraint_t S
Definition: joint-prismatic-unaligned.hpp:526
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::StDiagonalMatrixSOperationReturnType
ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType
Definition: joint-prismatic-unaligned.hpp:228
pinocchio::JointModelPrismaticUnalignedTpl::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::Matrix4
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
Definition: joint-prismatic-unaligned.hpp:45
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::axis
Vector3 & axis()
Definition: joint-prismatic-unaligned.hpp:393
pinocchio::impl::LhsMultiplicationOp< InertiaTpl< S1, O1 >, JointMotionSubspacePrismaticUnalignedTpl< S2, O2 > >::ReturnType
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
Definition: joint-prismatic-unaligned.hpp:422
pinocchio::JointDataPrismaticUnalignedTpl::v
Motion_t v
Definition: joint-prismatic-unaligned.hpp:527
pinocchio::MultiplicationOp< InertiaTpl< S1, O1 >, JointMotionSubspacePrismaticUnalignedTpl< S2, O2 > >::ReturnType
Eigen::Matrix< S2, 6, 1, O2 > ReturnType
Definition: joint-prismatic-unaligned.hpp:411
pinocchio::MotionPrismaticUnaligned
MotionPrismaticUnalignedTpl< context::Scalar > MotionPrismaticUnaligned
Definition: joint-prismatic-unaligned.hpp:20
pinocchio::impl::LhsMultiplicationOp< InertiaTpl< S1, O1 >, JointMotionSubspacePrismaticUnalignedTpl< S2, O2 > >::Inertia
InertiaTpl< S1, O1 > Inertia
Definition: joint-prismatic-unaligned.hpp:420
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::ConfigVector_t
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
Definition: joint-prismatic-unaligned.hpp:500
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: joint-prismatic-unaligned.hpp:43
pinocchio::JointDataPrismaticUnalignedTpl::classname
static std::string classname()
Definition: joint-prismatic-unaligned.hpp:563
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::transpose
TransposeConst transpose() const
Definition: joint-prismatic-unaligned.hpp:360
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::JointMotionSubspacePrismaticUnalignedTpl
JointMotionSubspacePrismaticUnalignedTpl()
Definition: joint-prismatic-unaligned.hpp:283
pinocchio::MultiplicationOp< Eigen::MatrixBase< M6Like >, JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::M6LikeColsNonConst
Eigen::internal::remove_const< M6LikeCols >::type M6LikeColsNonConst
Definition: joint-prismatic-unaligned.hpp:446
joint-base.hpp
pinocchio::traits< JointModelPrismaticUnalignedTpl< _Scalar, _Options > >::Scalar
_Scalar Scalar
Definition: joint-prismatic-unaligned.hpp:578
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::Vector3
traits< JointMotionSubspacePrismaticUnalignedTpl >::Vector3 Vector3
Definition: joint-prismatic-unaligned.hpp:281
x
x
pinocchio::MotionAlgebraAction< MotionPrismaticUnalignedTpl< Scalar, Options >, MotionDerived >::ReturnType
MotionTpl< Scalar, Options > ReturnType
Definition: joint-prismatic-unaligned.hpp:32
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::Bias_t
MotionZeroTpl< Scalar, Options > Bias_t
Definition: joint-prismatic-unaligned.hpp:493
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::__mult__
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) const
Definition: joint-prismatic-unaligned.hpp:295
pinocchio::JointModelPrismaticUnalignedTpl::Vector3
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
Definition: joint-prismatic-unaligned.hpp:596
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::TransposeConst
Definition: joint-prismatic-unaligned.hpp:328
pinocchio::JointDataPrismaticUnalignedTpl::joint_v
TangentVector_t joint_v
Definition: joint-prismatic-unaligned.hpp:523
pinocchio::JointModelPrismaticUnalignedTpl::createData
JointDataDerived createData() const
Definition: joint-prismatic-unaligned.hpp:617
axis
axis
pinocchio::JointModelPrismaticUnalignedTpl::cast
JointModelPrismaticUnalignedTpl< NewScalar, Options > cast() const
Definition: joint-prismatic-unaligned.hpp:693
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::MotionPlain
MotionTpl< Scalar, Options > MotionPlain
Definition: joint-prismatic-unaligned.hpp:55
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::Constraint_t
JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > Constraint_t
Definition: joint-prismatic-unaligned.hpp:490
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::HomogeneousMatrixType
Matrix4 HomogeneousMatrixType
Definition: joint-prismatic-unaligned.hpp:54
pinocchio::MotionPrismaticUnalignedTpl::se3Action_impl
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Definition: joint-prismatic-unaligned.hpp:107
pinocchio::JointModelPrismaticUnalignedTpl::calc_aba
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
Definition: joint-prismatic-unaligned.hpp:667
pinocchio::impl::LhsMultiplicationOp< Eigen::MatrixBase< M6Like >, JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::run
static ReturnType run(const Eigen::MatrixBase< M6Like > &Y, const Constraint &cru)
Definition: joint-prismatic-unaligned.hpp:464
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::Vector6
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
Definition: joint-prismatic-unaligned.hpp:44
pinocchio::JointDataPrismaticUnalignedTpl::JointDataPrismaticUnalignedTpl
JointDataPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
Definition: joint-prismatic-unaligned.hpp:550
pinocchio::MultiplicationOp< Eigen::MatrixBase< M6Like >, JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::Vector3
Constraint::Vector3 Vector3
Definition: joint-prismatic-unaligned.hpp:449
pinocchio::JointModelBase::idx_v
int idx_v() const
Definition: joint-model-base.hpp:164
pinocchio::ForceSetTpl
Definition: force-set.hpp:14
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
pinocchio::internal::comparison_eq
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
Definition: utils/static-if.hpp:120
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::ActionMatrixType
Matrix6 ActionMatrixType
Definition: joint-prismatic-unaligned.hpp:53
pinocchio::ConstraintForceSetOp
Return type of the Constraint::Transpose * ForceSet operation.
Definition: constraint-base.hpp:53
pinocchio::JointModelPrismaticUnalignedTpl
Definition: multibody/joint/fwd.hpp:94
pinocchio::JointDataPrismaticUnalignedTpl::UDinv
UD_t UDinv
Definition: joint-prismatic-unaligned.hpp:533
pinocchio::JointModelPrismaticUnalignedTpl::isEqual
bool isEqual(const JointModelPrismaticUnalignedTpl &other) const
Definition: joint-prismatic-unaligned.hpp:633
pinocchio::JointModelPrismaticUnalignedTpl::Base
JointModelBase< JointModelPrismaticUnalignedTpl > Base
Definition: joint-prismatic-unaligned.hpp:590
joint-motion-subspace.hpp
pinocchio::JointModelBase::idx_q
int idx_q() const
Definition: joint-model-base.hpp:160
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::TransposeConst::TransposeConst
TransposeConst(const JointMotionSubspacePrismaticUnalignedTpl &ref)
Definition: joint-prismatic-unaligned.hpp:332
pinocchio::SizeDepType::ColsReturn
Definition: matrix-block.hpp:43
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::JointModelDerived
JointModelPrismaticUnalignedTpl< Scalar, Options > JointModelDerived
Definition: joint-prismatic-unaligned.hpp:489
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::PlainReturnType
MotionPlain PlainReturnType
Definition: joint-prismatic-unaligned.hpp:56
pinocchio::ForceDense
Definition: context/casadi.hpp:34
pinocchio::MotionPrismaticUnalignedTpl::se3ActionInverse_impl
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
Definition: joint-prismatic-unaligned.hpp:132
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::AngularType
Vector3 AngularType
Definition: joint-prismatic-unaligned.hpp:49
pinocchio::SE3GroupAction< MotionPrismaticUnalignedTpl< Scalar, Options > >::ReturnType
MotionTpl< Scalar, Options > ReturnType
Definition: joint-prismatic-unaligned.hpp:26
PINOCCHIO_CONSTRAINT_TYPEDEF_TPL
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
Definition: constraint-base.hpp:36
pinocchio::traits< JointMotionSubspacePrismaticUnalignedTpl< _Scalar, _Options > >::Scalar
_Scalar Scalar
Definition: joint-prismatic-unaligned.hpp:208
pinocchio::operator^
EIGEN_STRONG_INLINE MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &m2)
Definition: joint-helical-unaligned.hpp:222
pinocchio::MotionPrismaticUnalignedTpl::motionAction
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
Definition: joint-prismatic-unaligned.hpp:140
pinocchio::impl::LhsMultiplicationOp< InertiaTpl< S1, O1 >, JointMotionSubspacePrismaticUnalignedTpl< S2, O2 > >::Constraint
JointMotionSubspacePrismaticUnalignedTpl< S2, O2 > Constraint
Definition: joint-prismatic-unaligned.hpp:421
pinocchio::ConstraintForceSetOp< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options >, ForceSet >::ReturnType
MatrixMatrixProduct< Eigen::Transpose< const Vector3 >, typename Eigen::MatrixBase< const ForceSet >::template NRowsBlockXpr< 3 >::Type >::type ReturnType
Definition: joint-prismatic-unaligned.hpp:266
pinocchio::JointModelPrismaticUnalignedTpl::axis
Vector3 axis
3d main axis of the joint.
Definition: joint-prismatic-unaligned.hpp:706
pinocchio::MotionPrismaticUnalignedTpl::isEqual_impl
bool isEqual_impl(const MotionPrismaticUnalignedTpl &other) const
Definition: joint-prismatic-unaligned.hpp:158
Y
Y
pinocchio::JointDataPrismaticUnalignedTpl::M
Transformation_t M
Definition: joint-prismatic-unaligned.hpp:525
pinocchio::ConstraintForceSetOp< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options >, ForceSet >::Vector3
traits< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::Vector3 Vector3
Definition: joint-prismatic-unaligned.hpp:263
pinocchio::traits
Common traits structure to fully define base classes for CRTP.
Definition: fwd.hpp:71
pinocchio::traits< JointDataPrismaticUnalignedTpl< _Scalar, _Options > >::JointDerived
JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
Definition: joint-prismatic-unaligned.hpp:509
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::U_t
Eigen::Matrix< Scalar, 6, NV, Options > U_t
Definition: joint-prismatic-unaligned.hpp:496
pinocchio::JointDataPrismaticUnalignedTpl::c
Bias_t c
Definition: joint-prismatic-unaligned.hpp:528
pinocchio::MotionPrismaticUnalignedTpl::MOTION_TYPEDEF_TPL
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL(MotionPrismaticUnalignedTpl)
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::Motion_t
MotionPrismaticUnalignedTpl< Scalar, Options > Motion_t
Definition: joint-prismatic-unaligned.hpp:492
pinocchio::impl::LhsMultiplicationOp< InertiaTpl< S1, O1 >, JointMotionSubspacePrismaticUnalignedTpl< S2, O2 > >::run
static ReturnType run(const Inertia &Y, const Constraint &cpu)
Definition: joint-prismatic-unaligned.hpp:424
PINOCCHIO_EIGEN_REF_TYPE
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Definition: eigen-macros.hpp:32
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::Scalar
_Scalar Scalar
Definition: joint-prismatic-unaligned.hpp:483
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::ConstLinearType
const typedef Vector3 ConstLinearType
Definition: joint-prismatic-unaligned.hpp:52
pinocchio::JointDataPrismaticUnalignedTpl::U
U_t U
Definition: joint-prismatic-unaligned.hpp:531
pinocchio::MotionPrismaticUnalignedTpl::axis
Vector3 & axis()
Definition: joint-prismatic-unaligned.hpp:177
pinocchio::JointMotionSubspaceTransposeBase
Definition: constraint-base.hpp:185
pinocchio::MotionTpl< Scalar, Options >
pinocchio::traits< JointPrismaticUnalignedTpl< _Scalar, _Options > >::D_t
Eigen::Matrix< Scalar, NV, NV, Options > D_t
Definition: joint-prismatic-unaligned.hpp:497
dcrba.NV
NV
Definition: dcrba.py:514
dpendulum.NQ
int NQ
Definition: dpendulum.py:8
pinocchio::JointDataPrismaticUnalignedTpl
Definition: multibody/joint/fwd.hpp:98
pinocchio::JointDataPrismaticUnalignedTpl::PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
meshcat-viewer.qs
qs
Definition: meshcat-viewer.py:127
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::axis
const Vector3 & axis() const
Definition: joint-prismatic-unaligned.hpp:389
pinocchio::MotionRef
Definition: context/casadi.hpp:38
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::matrix_impl
DenseBase matrix_impl() const
Definition: joint-prismatic-unaligned.hpp:371
pinocchio::MultiplicationOp< Eigen::MatrixBase< M6Like >, JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::M6LikeCols
SizeDepType< 3 >::ColsReturn< M6Like >::ConstType M6LikeCols
Definition: joint-prismatic-unaligned.hpp:445
pinocchio::JointDataPrismaticUnalignedTpl::JointDataPrismaticUnalignedTpl
JointDataPrismaticUnalignedTpl()
Definition: joint-prismatic-unaligned.hpp:536
pinocchio::MotionPrismaticUnalignedTpl::se3ActionInverse_impl
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Definition: joint-prismatic-unaligned.hpp:122
pinocchio::JointModelBase::isEqual
bool isEqual(const JointModelBase< OtherDerived > &) const
Definition: joint-model-base.hpp:242
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::motionAction
DenseBase motionAction(const MotionDense< MotionDerived > &v) const
Definition: joint-prismatic-unaligned.hpp:380
pinocchio::normalize
void normalize(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout)
Normalize a configuration vector.
Definition: joint-configuration.hpp:914
pinocchio::JointMotionSubspacePrismaticUnalignedTpl::TransposeConst::ref
const JointMotionSubspacePrismaticUnalignedTpl & ref
Definition: joint-prismatic-unaligned.hpp:331
pinocchio::MotionDense::angular
ConstAngularType angular() const
Definition: motion-base.hpp:32
pinocchio::TransformTranslationTpl
Definition: joint-translation.hpp:196
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::JointModelPrismaticUnalignedTpl::calc
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
Definition: joint-prismatic-unaligned.hpp:655
pinocchio::traits< MotionPrismaticUnalignedTpl< _Scalar, _Options > >::ConstAngularType
const typedef Vector3 ConstAngularType
Definition: joint-prismatic-unaligned.hpp:51
pinocchio::JointModelBase::id
JointIndex id() const
Definition: joint-model-base.hpp:168


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:48