9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
12 #include <pinocchio/multibody/fwd.hpp>
13 #include <pinocchio/spatial/se3.hpp>
15 #include "crocoddyl/core/residual-base.hpp"
16 #include "crocoddyl/core/utils/exception.hpp"
17 #include "crocoddyl/multibody/data/multibody.hpp"
18 #include "crocoddyl/multibody/fwd.hpp"
19 #include "crocoddyl/multibody/states/multibody.hpp"
38 template <
typename _Scalar>
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 typedef _Scalar Scalar;
51 typedef typename MathBase::VectorXs VectorXs;
52 typedef pinocchio::SE3Tpl<Scalar> SE3;
63 const pinocchio::FrameIndex
id,
64 const SE3& pref,
const std::size_t nu);
76 const pinocchio::FrameIndex
id,
87 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
88 const Eigen::Ref<const VectorXs>& x,
89 const Eigen::Ref<const VectorXs>& u);
98 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
99 const Eigen::Ref<const VectorXs>& x,
100 const Eigen::Ref<const VectorXs>& u);
121 void set_id(
const pinocchio::FrameIndex
id);
133 virtual void print(std::ostream& os)
const;
142 pinocchio::FrameIndex id_;
144 pinocchio::SE3Tpl<Scalar> oMf_inv_;
145 boost::shared_ptr<typename StateMultibody::PinocchioModel>
149 template <
typename _Scalar>
151 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
153 typedef _Scalar Scalar;
157 typedef typename MathBase::Matrix6xs Matrix6xs;
158 typedef typename MathBase::Matrix6s Matrix6s;
159 typedef typename MathBase::Vector6s Vector6s;
161 template <
template <
typename Scalar>
class Model>
164 :
Base(model, data),
rJf(6, 6),
fJf(6, model->get_state()->get_nv()) {
173 "Invalid argument: the shared data should be derived from "
174 "DataCollectorMultibody");
182 pinocchio::SE3Tpl<Scalar>
rMf;
197 #include "crocoddyl/multibody/residuals/frame-placement.hxx"
Abstract class for residual models.
boost::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
Frame placement residual.
ResidualModelFramePlacementTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref, const std::size_t nu)
Initialize the frame placement residual model.
ResidualModelFramePlacementTpl(boost::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.
virtual void print(std::ostream &os) const
Print relevant information of the frame-placement residual.
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 placement residual.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
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 placement residual.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the frame placement residual data.
void set_reference(const SE3 &reference)
Modify the reference frame placement.
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.