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/multibody/fwd.hpp" 15 #include "crocoddyl/core/residual-base.hpp" 16 #include "crocoddyl/multibody/states/multibody.hpp" 17 #include "crocoddyl/multibody/data/multibody.hpp" 18 #include "crocoddyl/core/utils/exception.hpp" 35 template <
typename _Scalar>
36 class ResidualModelFrameRotationTpl :
public ResidualModelAbstractTpl<_Scalar> {
38 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40 typedef _Scalar Scalar;
41 typedef MathBaseTpl<Scalar> MathBase;
42 typedef ResidualModelAbstractTpl<Scalar> Base;
43 typedef ResidualDataFrameRotationTpl<Scalar> Data;
44 typedef StateMultibodyTpl<Scalar> StateMultibody;
45 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
46 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
47 typedef typename MathBase::VectorXs VectorXs;
48 typedef typename MathBase::Matrix3s Matrix3s;
59 const Matrix3s& Rref,
const std::size_t nu);
71 const Matrix3s& Rref);
81 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
82 const Eigen::Ref<const VectorXs>& u);
91 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
92 const Eigen::Ref<const VectorXs>& u);
97 virtual boost::shared_ptr<ResidualDataAbstract>
createData(DataCollectorAbstract*
const data);
102 pinocchio::FrameIndex
get_id()
const;
112 void set_id(
const pinocchio::FrameIndex
id);
124 virtual void print(std::ostream& os)
const;
134 pinocchio::FrameIndex id_;
137 boost::shared_ptr<typename StateMultibody::PinocchioModel> pin_model_;
140 template <
typename _Scalar>
141 struct ResidualDataFrameRotationTpl :
public ResidualDataAbstractTpl<_Scalar> {
142 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
144 typedef _Scalar Scalar;
145 typedef MathBaseTpl<Scalar> MathBase;
146 typedef ResidualDataAbstractTpl<Scalar> Base;
147 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
148 typedef typename MathBase::Vector3s Vector3s;
149 typedef typename MathBase::Matrix3s Matrix3s;
150 typedef typename MathBase::Matrix3xs Matrix3xs;
151 typedef typename MathBase::Matrix6xs Matrix6xs;
153 template <
template <
typename Scalar>
class Model>
154 ResidualDataFrameRotationTpl(Model<Scalar>*
const model, DataCollectorAbstract*
const data)
155 : Base(model, data),
rJf(3, 3),
fJf(6, model->get_state()->get_nv()) {
161 DataCollectorMultibodyTpl<Scalar>* d =
dynamic_cast<DataCollectorMultibodyTpl<Scalar>*
>(
shared);
163 throw_pretty(
"Invalid argument: the shared data should be derived from DataCollectorMultibody");
186 #include "crocoddyl/multibody/residuals/frame-rotation.hxx" 188 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_ pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.
Matrix3s rRf
Rotation error of the frame.
bool u_dependent_
Label that indicates if the residual function depends on u.
Matrix6xs fJf
Local Jacobian of the frame.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the frame rotation residual data.
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.
std::size_t nu_
Control dimension.
void set_id(const pinocchio::FrameIndex id)
Modify the reference frame id.
virtual void print(std::ostream &os) const
Print relevant information of the frame-rotation residual.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
MatrixXs Ru
Jacobian of the residual vector with respect the control.
boost::shared_ptr< StateAbstract > state_
State description.
VectorXs unone_
No control vector.
const Matrix3s & get_reference() const
Return the reference frame rotation.
void set_reference(const Matrix3s &reference)
Modify the reference frame rotation.
bool v_dependent_
Label that indicates if the residual function depends on v.
VectorXs r
Residual vector.
DataCollectorAbstract * shared
Shared data allocated by the action model.
Matrix3s rJf
Error Jacobian of the frame.
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.
ResidualModelFrameRotationTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Matrix3s &Rref, const std::size_t nu)
Initialize the frame rotation residual model.