5 #ifndef __pinocchio_joint_revolute_unbounded_hpp__ 6 #define __pinocchio_joint_revolute_unbounded_hpp__ 8 #include "pinocchio/math/fwd.hpp" 9 #include "pinocchio/math/sincos.hpp" 10 #include "pinocchio/spatial/inertia.hpp" 11 #include "pinocchio/multibody/joint/joint-base.hpp" 12 #include "pinocchio/multibody/joint/joint-revolute.hpp" 19 template<
typename _Scalar,
int _Options,
int axis>
36 typedef Eigen::Matrix<Scalar,6,NV,Options>
U_t;
37 typedef Eigen::Matrix<Scalar,NV,NV,Options>
D_t;
38 typedef Eigen::Matrix<Scalar,6,NV,Options>
UD_t;
46 template<
typename Scalar,
int Options,
int axis>
50 template<
typename Scalar,
int Options,
int axis>
54 template<
typename _Scalar,
int _Options,
int axis>
57 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82 return std::string(
"JointDataRUB") + axisLabel<axis>();
84 std::string
shortname()
const {
return classname(); }
88 template<
typename NewScalar,
typename Scalar,
int Options,
int axis>
94 template<
typename _Scalar,
int _Options,
int axis>
96 :
public JointModelBase< JointModelRevoluteUnboundedTpl<_Scalar,_Options,axis> >
98 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
109 JointDataDerived
createData()
const {
return JointDataDerived(); }
111 template<
typename ConfigVector>
112 void calc(JointDataDerived & data,
113 const typename Eigen::MatrixBase<ConfigVector> & qs)
const 116 typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type
117 &
q = qs.template segment<NQ> (
idx_q());
119 const OtherScalar & ca =
q(0);
120 const OtherScalar & sa =
q(1);
122 data.M.setValues(sa,ca);
125 template<
typename ConfigVector,
typename TangentVector>
126 void calc(JointDataDerived & data,
127 const typename Eigen::MatrixBase<ConfigVector> & qs,
128 const typename Eigen::MatrixBase<TangentVector> & vs)
const 130 calc(data,qs.derived());
132 data.v.angularRate() =
static_cast<Scalar>(vs[
idx_v()]);
135 template<
typename Matrix6Like>
136 void calc_aba(JointDataDerived & data,
const Eigen::MatrixBase<Matrix6Like> & I,
const bool update_I)
const 138 data.U = I.col(Inertia::ANGULAR +
axis);
139 data.Dinv[0] = (
Scalar)(1)/I(Inertia::ANGULAR +
axis,Inertia::ANGULAR +
axis);
140 data.UDinv.noalias() = data.U * data.Dinv[0];
148 return std::string(
"JointModelRUB") + axisLabel<axis>();
153 template<
typename NewScalar>
166 template<
typename ConfigVectorIn,
typename Scalar,
typename ConfigVectorOut>
167 static void run(
const Eigen::MatrixBase<ConfigVectorIn> &
q,
170 const Eigen::MatrixBase<ConfigVectorOut> & dest)
172 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(ConfigVectorIn,2);
173 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(ConfigVectorOut,2);
182 SINCOS(theta_transform,&dest_.coeffRef(1),&dest_.coeffRef(0));
186 template<
typename Scalar,
int Options,
int axis>
206 #include <boost/type_traits.hpp> 210 template<
typename Scalar,
int Options,
int axis>
212 :
public integral_constant<bool,true> {};
214 template<
typename Scalar,
int Options,
int axis>
216 :
public integral_constant<bool,true> {};
218 template<
typename Scalar,
int Options,
int axis>
220 :
public integral_constant<bool,true> {};
222 template<
typename Scalar,
int Options,
int axis>
224 :
public integral_constant<bool,true> {};
227 #endif // ifndef __pinocchio_joint_revolute_unbounded_hpp__
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnboundedTpl< _Scalar, _Options, axis > JointDerived
ConstraintRevoluteTpl< Scalar, Options, axis > Constraint_t
Eigen::Matrix< Scalar, 6, NV, Options > U_t
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
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...
JointRevoluteUnboundedTpl< double, 0, 0 > JointRUBX
JointRevoluteUnboundedTpl< double, 0, 2 > JointRUBZ
JointModelRevoluteUnboundedTpl< double, 0, 1 > JointModelRUBY
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain...
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnboundedTpl< _Scalar, _Options, axis > JointDerived
JointModelRevoluteUnboundedTpl< double, 0, 2 > JointModelRUBZ
JointModelRevoluteUnboundedTpl< Scalar, Options, axis > JointModelDerived
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
JointDataRevoluteUnboundedTpl< Scalar, Options, axis > JointDataDerived
JointDataRevoluteUnboundedTpl< double, 0, 0 > JointDataRUBX
Eigen::Matrix< Scalar, NV, NV, Options > D_t
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
MotionZeroTpl< Scalar, Options > Bias_t
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Constraint_t S
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
JointDataDerived createData() const
JointRevoluteUnboundedTpl< double, 0, 1 > JointRUBY
JointModelRevoluteUnboundedTpl< NewScalar, Options, axis > cast() const
std::string shortname() const
JointDataRevoluteUnboundedTpl< double, 0, 2 > JointDataRUBZ
JointRevoluteUnboundedTpl< Scalar, Options, axis > JointDerived
MotionRevoluteTpl< Scalar, Options, axis > Motion_t
void SINCOS(const S1 &a, S2 *sa, S3 *ca)
Computes sin/cos values of a given input scalar.
JointRevoluteTpl< Scalar, _Options, axis > JointDerivedBase
static std::string classname()
JointRevoluteUnboundedTpl< Scalar, Options, axis > JointDerived
Main pinocchio namespace.
static std::string classname()
JointModelRevoluteUnboundedTpl< NewScalar, Options, axis > type
void setIndexes(JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v)
Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic...
TransformRevoluteTpl< Scalar, Options, axis > Transformation_t
Common traits structure to fully define base classes for CRTP.
JointModelBase< JointModelRevoluteUnboundedTpl > Base
std::string shortname() const
JointDataRevoluteUnboundedTpl()
JointDataRevoluteUnboundedTpl< double, 0, 1 > JointDataRUBY
JointModelRevoluteUnboundedTpl< double, 0, 0 > JointModelRUBX
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type...
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)