Crocoddyl
 
Loading...
Searching...
No Matches
frame-rotation.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_ROTATION_HPP_
11#define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_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:
38 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40
41 typedef _Scalar Scalar;
48 typedef typename MathBase::VectorXs VectorXs;
49 typedef typename MathBase::Matrix3s Matrix3s;
50
59 ResidualModelFrameRotationTpl(std::shared_ptr<StateMultibody> state,
60 const pinocchio::FrameIndex id,
61 const Matrix3s& Rref, const std::size_t nu);
62
72 ResidualModelFrameRotationTpl(std::shared_ptr<StateMultibody> state,
73 const pinocchio::FrameIndex id,
74 const Matrix3s& Rref);
75 virtual ~ResidualModelFrameRotationTpl() = default;
76
84 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
85 const Eigen::Ref<const VectorXs>& x,
86 const Eigen::Ref<const VectorXs>& u) override;
87
95 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
96 const Eigen::Ref<const VectorXs>& x,
97 const Eigen::Ref<const VectorXs>& u) override;
98
102 virtual std::shared_ptr<ResidualDataAbstract> createData(
103 DataCollectorAbstract* const data) override;
104
114 template <typename NewScalar>
116
120 pinocchio::FrameIndex get_id() const;
121
125 const Matrix3s& get_reference() const;
126
130 void set_id(const pinocchio::FrameIndex id);
131
135 void set_reference(const Matrix3s& reference);
136
142 virtual void print(std::ostream& os) const override;
143
144 protected:
145 using Base::nu_;
146 using Base::state_;
147 using Base::u_dependent_;
148 using Base::v_dependent_;
149
150 private:
151 pinocchio::FrameIndex id_;
152 Matrix3s Rref_;
153 Matrix3s oRf_inv_;
154 std::shared_ptr<typename StateMultibody::PinocchioModel>
155 pin_model_;
156};
157
158template <typename _Scalar>
160 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
161
162 typedef _Scalar Scalar;
166 typedef typename MathBase::Vector3s Vector3s;
167 typedef typename MathBase::Matrix3s Matrix3s;
168 typedef typename MathBase::Matrix3xs Matrix3xs;
169 typedef typename MathBase::Matrix6xs Matrix6xs;
170
171 template <template <typename Scalar> class Model>
172 ResidualDataFrameRotationTpl(Model<Scalar>* const model,
173 DataCollectorAbstract* const data)
174 : Base(model, data), rJf(3, 3), fJf(6, model->get_state()->get_nv()) {
175 r.setZero();
176 rRf.setIdentity();
177 rJf.setZero();
178 fJf.setZero();
179 // Check that proper shared data has been passed
182 if (d == NULL) {
183 throw_pretty(
184 "Invalid argument: the shared data should be derived from "
185 "DataCollectorMultibody");
186 }
187
188 // Avoids data casting at runtime
189 pinocchio = d->pinocchio;
190 }
191 virtual ~ResidualDataFrameRotationTpl() = default;
192
193 pinocchio::DataTpl<Scalar>* pinocchio;
194 Matrix3s rRf;
195 Matrix3s rJf;
196 Matrix6xs fJf;
197
198 using Base::r;
199 using Base::Ru;
200 using Base::Rx;
201 using Base::shared;
202};
203
204} // namespace crocoddyl
205
206/* --- Details -------------------------------------------------------------- */
207/* --- Details -------------------------------------------------------------- */
208/* --- Details -------------------------------------------------------------- */
209#include "crocoddyl/multibody/residuals/frame-rotation.hxx"
210
211CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
213CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
215
216#endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
const Matrix3s & get_reference() const
Return the reference frame rotation.
void set_reference(const Matrix3s &reference)
Modify the reference frame rotation.
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 rotation residual.
ResidualModelFrameRotationTpl< NewScalar > cast() const
Cast the frame-rotation residual model to a different scalar type.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data) override
Create the frame rotation residual data.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
ResidualModelFrameRotationTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Matrix3s &Rref)
Initialize the frame rotation residual model.
ResidualModelFrameRotationTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Matrix3s &Rref, const std::size_t nu)
Initialize the frame rotation 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 rotation residual.
virtual void print(std::ostream &os) const override
Print relevant information of the frame-rotation 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.
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.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.