6#include <pinocchio/multibody/model.hpp>
7#include <pinocchio/multibody/frame.hpp>
15template <
typename _Scalar>
18 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
23 using Model = pinocchio::ModelTpl<Scalar>;
25 using SE3 = pinocchio::SE3Tpl<Scalar>;
32 const pinocchio::FrameIndex frame_id)
51 return std::make_shared<Data>(*
this);
59template <
typename Scalar>
61 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63 using PinData = pinocchio::DataTpl<Scalar>;
64 using SE3 = pinocchio::SE3Tpl<Scalar>;
80#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
81#include "aligator/modelling/multibody/frame-placement.txx"
pinocchio::DataTpl< Scalar > PinData
FramePlacementDataTpl(const FramePlacementResidualTpl< Scalar > &model)
StageFunctionDataTpl< Scalar > Base
math_types< Scalar >::Matrix6s rJf_
Jacobian of the error.
math_types< Scalar >::Matrix6Xs fJf_
Jacobian of the error, local frame.
SE3 rMf_
Placement error of the frame.
PinData pin_data_
Pinocchio data object.
pinocchio::SE3Tpl< Scalar > SE3
StageFunctionDataTpl< Scalar > BaseData
FramePlacementResidualTpl(const int ndx, const int nu, const Model &model, const SE3 &frame, const pinocchio::FrameIndex frame_id)
void setReference(const SE3 &p_new)
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
void evaluate(const ConstVectorRef &x, BaseData &data) const
void computeJacobians(const ConstVectorRef &x, BaseData &data) const
FramePlacementDataTpl< Scalar > Data
ALIGATOR_UNARY_FUNCTION_INTERFACE(Scalar)
pinocchio::ModelTpl< Scalar > Model
xyz::polymorphic< ManifoldAbstractTpl< Scalar > > PolyManifold
shared_ptr< BaseData > createData() const
Instantiate a Data object.
const SE3 & getReference() const
pinocchio::SE3Tpl< Scalar > SE3
Base struct for function data.
StageFunctionDataTpl(const int ndx, const int nu, const int nr)
const int nu
Control dimension.
Represents unary functions of the form , with no control (or next-state) arguments.
StageFunctionTpl< Scalar > Base
pinocchio::FrameIndex pin_frame_id_
Typedefs for math (Eigen vectors, matrices) depending on scalar type.