Crocoddyl
 
Loading...
Searching...
No Matches
frame-placement.hpp
1
2// BSD 3-Clause License
3//
4// Copyright (C) 2021-2025, LAAS-CNRS, University of Edinburgh,
5// Heriot-Watt University
6// Copyright note valid unless otherwise stated in individual files.
7// All rights reserved.
9
10#ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
11#define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
12
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"
17
18namespace crocoddyl {
19
35template <typename _Scalar>
37 : public ResidualModelAbstractTpl<_Scalar> {
38 public:
39 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41
42 typedef _Scalar Scalar;
49 typedef typename MathBase::VectorXs VectorXs;
50 typedef pinocchio::SE3Tpl<Scalar> SE3;
51
60 ResidualModelFramePlacementTpl(std::shared_ptr<StateMultibody> state,
61 const pinocchio::FrameIndex id,
62 const SE3& pref, const std::size_t nu);
63
73 ResidualModelFramePlacementTpl(std::shared_ptr<StateMultibody> state,
74 const pinocchio::FrameIndex id,
75 const SE3& pref);
76 virtual ~ResidualModelFramePlacementTpl() = default;
77
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;
88
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;
99
103 virtual std::shared_ptr<ResidualDataAbstract> createData(
104 DataCollectorAbstract* const data) override;
105
115 template <typename NewScalar>
117
121 pinocchio::FrameIndex get_id() const;
122
126 const SE3& get_reference() const;
127
131 void set_id(const pinocchio::FrameIndex id);
132
136 void set_reference(const SE3& reference);
137
143 virtual void print(std::ostream& os) const override;
144
145 protected:
146 using Base::nu_;
147 using Base::state_;
148 using Base::u_dependent_;
149 using Base::v_dependent_;
150
151 private:
152 pinocchio::FrameIndex id_;
153 SE3 pref_;
154 pinocchio::SE3Tpl<Scalar> oMf_inv_;
155 std::shared_ptr<typename StateMultibody::PinocchioModel>
156 pin_model_;
157};
158
159template <typename _Scalar>
161 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
162
163 typedef _Scalar Scalar;
167 typedef typename MathBase::Matrix6xs Matrix6xs;
168 typedef typename MathBase::Matrix6s Matrix6s;
169 typedef typename MathBase::Vector6s Vector6s;
170
171 template <template <typename Scalar> class Model>
172 ResidualDataFramePlacementTpl(Model<Scalar>* const model,
173 DataCollectorAbstract* const data)
174 : Base(model, data), rJf(6, 6), fJf(6, model->get_state()->get_nv()) {
175 r.setZero();
176 rJf.setZero();
177 fJf.setZero();
178 // Check that proper shared data has been passed
181 if (d == NULL) {
182 throw_pretty(
183 "Invalid argument: the shared data should be derived from "
184 "DataCollectorMultibody");
185 }
186
187 // Avoids data casting at runtime
188 pinocchio = d->pinocchio;
189 }
190 virtual ~ResidualDataFramePlacementTpl() = default;
191
192 pinocchio::DataTpl<Scalar>* pinocchio;
193 pinocchio::SE3Tpl<Scalar> rMf;
194 Matrix6s rJf;
195 Matrix6xs fJf;
196
197 using Base::r;
198 using Base::Ru;
199 using Base::Rx;
200 using Base::shared;
201};
202
203} // namespace crocoddyl
204
205/* --- Details -------------------------------------------------------------- */
206/* --- Details -------------------------------------------------------------- */
207/* --- Details -------------------------------------------------------------- */
208#include "crocoddyl/multibody/residuals/frame-placement.hxx"
209
210CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
212CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
214
215#endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
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.
Definition multibody.hpp:34
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.
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.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.