10#ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_VELOCITY_HPP_
11#define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_VELOCITY_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"
36template <
typename _Scalar>
39 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42 typedef _Scalar Scalar;
49 typedef pinocchio::MotionTpl<Scalar> Motion;
50 typedef typename MathBase::VectorXs VectorXs;
63 const pinocchio::FrameIndex
id,
65 const pinocchio::ReferenceFrame type,
66 const std::size_t nu);
80 const pinocchio::FrameIndex
id,
82 const pinocchio::ReferenceFrame type);
92 virtual void calc(
const std::shared_ptr<ResidualDataAbstract>& data,
93 const Eigen::Ref<const VectorXs>& x,
94 const Eigen::Ref<const VectorXs>& u)
override;
103 virtual void calcDiff(
const std::shared_ptr<ResidualDataAbstract>& data,
104 const Eigen::Ref<const VectorXs>& x,
105 const Eigen::Ref<const VectorXs>& u)
override;
122 template <
typename NewScalar>
143 void set_id(
const pinocchio::FrameIndex
id);
153 void set_type(
const pinocchio::ReferenceFrame type);
160 virtual void print(std::ostream& os)
const override;
169 pinocchio::FrameIndex id_;
171 pinocchio::ReferenceFrame type_;
172 std::shared_ptr<typename StateMultibody::PinocchioModel>
176template <
typename _Scalar>
178 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
180 typedef _Scalar Scalar;
184 typedef typename MathBase::Matrix6xs Matrix6xs;
186 template <
template <
typename Scalar>
class Model>
189 :
Base(model, data) {
195 "Invalid argument: the shared data should be derived from "
196 "DataCollectorMultibody");
216#include "crocoddyl/multibody/residuals/frame-velocity.hxx"
218CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
220CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
std::size_t nr_
Residual vector dimension.
void set_reference(const Motion &velocity)
Modify reference velocity.
void set_id(const pinocchio::FrameIndex id)
Modify 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 Jacobians of the frame velocity residual.
ResidualModelFrameVelocityTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Motion &vref, const pinocchio::ReferenceFrame type, const std::size_t nu)
Initialize the frame velocity residual model.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data) override
Create the frame velocity residual data.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
void set_type(const pinocchio::ReferenceFrame type)
Modify reference type of velocity.
const Motion & get_reference() const
Return the reference velocity.
pinocchio::ReferenceFrame get_type() const
Return the reference type of velocity.
ResidualModelFrameVelocityTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Motion &vref, const pinocchio::ReferenceFrame type)
Initialize the frame velocity residual model.
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 velocity residual vector.
virtual void print(std::ostream &os) const override
Print relevant information of the frame-velocity residual.
ResidualModelFrameVelocityTpl< NewScalar > cast() const
Cast the frame-velocity residual model to a different scalar type.
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.
DataCollectorAbstract * shared
Shared data allocated by the action model.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.