9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
12 #include <pinocchio/multibody/fwd.hpp>
14 #include "crocoddyl/core/residual-base.hpp"
15 #include "crocoddyl/core/utils/exception.hpp"
16 #include "crocoddyl/multibody/data/multibody.hpp"
17 #include "crocoddyl/multibody/fwd.hpp"
18 #include "crocoddyl/multibody/states/multibody.hpp"
37 template <
typename _Scalar>
40 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42 typedef _Scalar Scalar;
49 typedef typename MathBase::VectorXs VectorXs;
50 typedef typename MathBase::Matrix3s Matrix3s;
61 const pinocchio::FrameIndex
id,
62 const Matrix3s& Rref,
const std::size_t nu);
74 const pinocchio::FrameIndex
id,
75 const Matrix3s& Rref);
85 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
86 const Eigen::Ref<const VectorXs>& x,
87 const Eigen::Ref<const VectorXs>& u);
96 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
97 const Eigen::Ref<const VectorXs>& x,
98 const Eigen::Ref<const VectorXs>& u);
119 void set_id(
const pinocchio::FrameIndex
id);
131 virtual void print(std::ostream& os)
const;
140 pinocchio::FrameIndex id_;
143 boost::shared_ptr<typename StateMultibody::PinocchioModel>
147 template <
typename _Scalar>
149 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
151 typedef _Scalar Scalar;
155 typedef typename MathBase::Vector3s Vector3s;
156 typedef typename MathBase::Matrix3s Matrix3s;
157 typedef typename MathBase::Matrix3xs Matrix3xs;
158 typedef typename MathBase::Matrix6xs Matrix6xs;
160 template <
template <
typename Scalar>
class Model>
163 :
Base(model, data),
rJf(3, 3),
fJf(6, model->get_state()->get_nv()) {
173 "Invalid argument: the shared data should be derived from "
174 "DataCollectorMultibody");
197 #include "crocoddyl/multibody/residuals/frame-rotation.hxx"
Abstract class for residual models.
boost::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
virtual void print(std::ostream &os) const
Print relevant information of the frame-rotation residual.
void set_reference(const Matrix3s &reference)
Modify the reference frame rotation.
ResidualModelFrameRotationTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Matrix3s &Rref)
Initialize the frame rotation residual model.
void set_id(const pinocchio::FrameIndex id)
Modify the reference frame id.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the frame rotation residual.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
ResidualModelFrameRotationTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Matrix3s &Rref, const std::size_t nu)
Initialize the frame rotation residual model.
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the frame rotation residual.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the frame rotation residual data.
const Matrix3s & get_reference() const
Return the reference frame rotation.
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.
Matrix3s rRf
Rotation error of the frame.
Matrix3s 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.