10#ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
11#define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
13#include "crocoddyl/core/residual-base.hpp"
14#include "crocoddyl/multibody/data/multibody.hpp"
15#include "crocoddyl/multibody/fwd.hpp"
16#include "crocoddyl/multibody/states/multibody.hpp"
35template <
typename _Scalar>
39 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42 typedef _Scalar Scalar;
49 typedef typename MathBase::VectorXs VectorXs;
50 typedef pinocchio::SE3Tpl<Scalar> SE3;
61 const pinocchio::FrameIndex
id,
62 const SE3& pref,
const std::size_t nu);
74 const pinocchio::FrameIndex
id,
85 virtual void calc(
const std::shared_ptr<ResidualDataAbstract>& data,
86 const Eigen::Ref<const VectorXs>& x,
87 const Eigen::Ref<const VectorXs>& u)
override;
96 virtual void calcDiff(
const std::shared_ptr<ResidualDataAbstract>& data,
97 const Eigen::Ref<const VectorXs>& x,
98 const Eigen::Ref<const VectorXs>& u)
override;
115 template <
typename NewScalar>
131 void set_id(
const pinocchio::FrameIndex
id);
143 virtual void print(std::ostream& os)
const override;
152 pinocchio::FrameIndex id_;
154 pinocchio::SE3Tpl<Scalar> oMf_inv_;
155 std::shared_ptr<typename StateMultibody::PinocchioModel>
159template <
typename _Scalar>
161 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
163 typedef _Scalar Scalar;
167 typedef typename MathBase::Matrix6xs Matrix6xs;
168 typedef typename MathBase::Matrix6s Matrix6s;
169 typedef typename MathBase::Vector6s Vector6s;
171 template <
template <
typename Scalar>
class Model>
174 :
Base(model, data),
rJf(6, 6),
fJf(6, model->get_state()->get_nv()) {
183 "Invalid argument: the shared data should be derived from "
184 "DataCollectorMultibody");
193 pinocchio::SE3Tpl<Scalar>
rMf;
208#include "crocoddyl/multibody/residuals/frame-placement.hxx"
210CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
212CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
Frame placement residual.
ResidualModelFramePlacementTpl< NewScalar > cast() const
Cast the frame-placement residual model to a different scalar type.
void set_id(const pinocchio::FrameIndex id)
Modify the reference frame id.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the derivatives of the frame placement residual.
ResidualModelFramePlacementTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref, const std::size_t nu)
Initialize the frame placement residual model.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data) override
Create the frame placement residual data.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
ResidualModelFramePlacementTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref)
Initialize the frame placement residual model.
const SE3 & get_reference() const
Return the reference frame placement.
void set_reference(const SE3 &reference)
Modify the reference frame placement.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the frame placement residual.
virtual void print(std::ostream &os) const override
Print relevant information of the frame-placement residual.
State multibody representation.
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
DataCollectorAbstract * shared
Shared data allocated by the action model.
VectorXs r
Residual vector.
pinocchio::SE3Tpl< Scalar > rMf
Error frame placement of the frame.
Matrix6s rJf
Error Jacobian of the frame.
Matrix6xs fJf
Local Jacobian of the frame.
DataCollectorAbstract * shared
Shared data allocated by the action model.
VectorXs r
Residual vector.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.