Go to the documentation of this file.
5 #ifndef __pinocchio_multibody_joint_revolute_unbounded_unaligned_hpp__
6 #define __pinocchio_multibody_joint_revolute_unbounded_unaligned_hpp__
18 template<
typename Scalar,
int Options = 0>
21 template<
typename _Scalar,
int _Options>
44 typedef Eigen::Matrix<Scalar, 6, NV, Options>
F_t;
47 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
48 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
49 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
54 template<
typename _Scalar,
int _Options>
61 template<
typename _Scalar,
int _Options>
68 template<
typename _Scalar,
int _Options>
70 :
public JointDataBase<JointDataRevoluteUnboundedUnalignedTpl<_Scalar, _Options>>
72 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
93 ,
joint_v(TangentVector_t::Zero())
94 ,
M(Transformation_t::Identity())
104 template<
typename Vector3Like>
107 ,
joint_v(TangentVector_t::Zero())
108 ,
M(Transformation_t::Identity())
113 ,
UDinv(UD_t::Zero())
120 return std::string(
"JointDataRevoluteUnboundedUnalignedTpl");
131 template<
typename _Scalar,
int _Options>
132 struct JointModelRevoluteUnboundedUnalignedTpl
133 :
public JointModelBase<JointModelRevoluteUnboundedUnalignedTpl<_Scalar, _Options>>
135 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
138 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
158 template<
typename Vector3Like>
162 EIGEN_STATIC_ASSERT_VECTOR_ONLY(Vector3Like);
168 return JointDataDerived(
axis);
173 return {
false,
false};
187 template<
typename ConfigVector>
188 void calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
198 template<
typename TangentVector>
200 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
204 data.v.angularRate() =
data.joint_v[0];
207 template<
typename ConfigVector,
typename TangentVector>
209 JointDataDerived &
data,
210 const typename Eigen::MatrixBase<ConfigVector> &
qs,
211 const typename Eigen::MatrixBase<TangentVector> & vs)
const
215 data.v.angularRate() =
data.joint_v[0];
218 template<
typename VectorLike,
typename Matrix6Like>
220 JointDataDerived &
data,
221 const Eigen::MatrixBase<VectorLike> & armature,
222 const Eigen::MatrixBase<Matrix6Like> & I,
223 const bool update_I)
const
225 data.U.noalias() = I.template middleCols<3>(Motion::ANGULAR) *
axis;
227 Scalar(1) / (
axis.dot(
data.U.template segment<3>(Motion::ANGULAR)) + armature[0]);
236 return std::string(
"JointModelRevoluteUnboundedUnaligned");
244 template<
typename NewScalar>
248 ReturnType
res(
axis.template cast<NewScalar>());
262 #include <boost/type_traits.hpp>
266 template<
typename Scalar,
int Options>
267 struct has_nothrow_constructor<
269 :
public integral_constant<bool, true>
273 template<
typename Scalar,
int Options>
275 :
public integral_constant<bool, true>
279 template<
typename Scalar,
int Options>
280 struct has_nothrow_constructor<
282 :
public integral_constant<bool, true>
286 template<
typename Scalar,
int Options>
288 :
public integral_constant<bool, true>
293 #endif // ifndef __pinocchio_multibody_joint_revolute_unbounded_unaligned_hpp__
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
const std::vector< bool > hasConfigurationLimitInTangent() const
JointDataRevoluteUnboundedUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
JointModelRevoluteUnboundedUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
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.
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
JointModelRevoluteUnboundedUnalignedTpl(const Scalar &x, const Scalar &y, const Scalar &z)
JointMotionSubspaceRevoluteUnalignedTpl< Scalar, Options > Constraint_t
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...
JointModelRevoluteUnboundedUnalignedTpl< Scalar, Options > JointModelDerived
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
SE3Tpl< Scalar, Options > Transformation_t
JointDataRevoluteUnboundedUnalignedTpl< Scalar, Options > JointDataDerived
void setIndexes(JointIndex id, int q, int v)
std::string shortname() const
Eigen::Matrix< Scalar, 6, NV, Options > F_t
JointRevoluteUnboundedUnalignedTpl< _Scalar, _Options > JointDerived
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
JointRevoluteUnboundedUnalignedTpl< _Scalar, _Options > JointDerived
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
Eigen::Matrix< Scalar, NV, NV, Options > D_t
Eigen::Matrix< Scalar, 6, NV, Options > U_t
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
Free-flyer joint in .
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnboundedUnalignedTpl< _Scalar, _Options > JointDerived
void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnboundedUnalignedTpl< _Scalar, _Options > JointDerived
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
MotionZeroTpl< Scalar, Options > Bias_t
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
JointDataDerived createData() const
MotionRevoluteUnalignedTpl< Scalar, Options > Motion_t
std::string shortname() const
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Vector3 axis
axis of rotation of the joint.
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
Computes a rotation matrix from a vector and values of sin and cos orientations values.
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
const std::vector< bool > hasConfigurationLimit() const
static std::string classname()
JointDataRevoluteUnboundedUnalignedTpl()
static std::string classname()
JointModelRevoluteUnboundedUnalignedTpl()
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
Common traits structure to fully define base classes for CRTP.
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
JointModelBase< JointModelRevoluteUnboundedUnalignedTpl > Base
bool isEqual(const JointModelBase< OtherDerived > &) const
void normalize(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout)
Normalize a configuration vector.
JointModelRevoluteUnboundedUnalignedTpl< NewScalar, Options > cast() const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
Main pinocchio namespace.
bool isEqual(const JointModelRevoluteUnboundedUnalignedTpl &other) const
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:46