6#include <pinocchio/multibody/model.hpp>
12template <
typename _Scalar>
19 using Model = pinocchio::ModelTpl<Scalar>;
20 using SE3 = pinocchio::SE3Tpl<Scalar>;
26 const Vector3s &dcm_ref,
const double alpha)
42 return std::make_shared<Data>(*
this);
50template <
typename Scalar>
52 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54 using PinData = pinocchio::DataTpl<Scalar>;
66#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
67#include "./dcm-position.txx"
math_types< Scalar >::Matrix3Xs fJf_
Jacobian of the error.
pinocchio::DataTpl< Scalar > PinData
PinData pin_data_
Pinocchio data object.
DCMPositionDataTpl(const DCMPositionResidualTpl< Scalar > &model)
StageFunctionDataTpl< Scalar > Base
ALIGATOR_UNARY_FUNCTION_INTERFACE(Scalar)
typename Base::Data BaseData
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
DCMPositionResidualTpl(const int ndx, const int nu, const Model &model, const Vector3s &dcm_ref, const double alpha)
pinocchio::ModelTpl< Scalar > Model
pinocchio::SE3Tpl< Scalar > SE3
DCMPositionDataTpl< Scalar > Data
void computeJacobians(const ConstVectorRef &x, BaseData &data) const
void setReference(const Eigen::Ref< const Vector3s > &new_ref)
shared_ptr< BaseData > createData() const
Instantiate a Data object.
void evaluate(const ConstVectorRef &x, BaseData &data) const
const Vector3s & getReference() const
StageFunctionDataTpl(const int ndx, const int nu, const int nr)
const int nu
Control dimension.
StageFunctionDataTpl< Scalar > Data
Represents unary functions of the form , with no control (or next-state) arguments.
StageFunctionTpl< Scalar > Base
Typedefs for math (Eigen vectors, matrices) depending on scalar type.