Crocoddyl
 
Loading...
Searching...
No Matches
frame-velocity.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_VELOCITY_HPP_
11#define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_VELOCITY_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
36template <typename _Scalar>
38 public:
39 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41
42 typedef _Scalar Scalar;
49 typedef pinocchio::MotionTpl<Scalar> Motion;
50 typedef typename MathBase::VectorXs VectorXs;
51
62 ResidualModelFrameVelocityTpl(std::shared_ptr<StateMultibody> state,
63 const pinocchio::FrameIndex id,
64 const Motion& vref,
65 const pinocchio::ReferenceFrame type,
66 const std::size_t nu);
67
79 ResidualModelFrameVelocityTpl(std::shared_ptr<StateMultibody> state,
80 const pinocchio::FrameIndex id,
81 const Motion& vref,
82 const pinocchio::ReferenceFrame type);
83 virtual ~ResidualModelFrameVelocityTpl() = default;
84
92 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
93 const Eigen::Ref<const VectorXs>& x,
94 const Eigen::Ref<const VectorXs>& u) override;
95
103 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
104 const Eigen::Ref<const VectorXs>& x,
105 const Eigen::Ref<const VectorXs>& u) override;
106
110 virtual std::shared_ptr<ResidualDataAbstract> createData(
111 DataCollectorAbstract* const data) override;
112
122 template <typename NewScalar>
124
128 pinocchio::FrameIndex get_id() const;
129
133 const Motion& get_reference() const;
134
138 pinocchio::ReferenceFrame get_type() const;
139
143 void set_id(const pinocchio::FrameIndex id);
144
148 void set_reference(const Motion& velocity);
149
153 void set_type(const pinocchio::ReferenceFrame type);
154
160 virtual void print(std::ostream& os) const override;
161
162 protected:
163 using Base::nr_;
164 using Base::nu_;
165 using Base::state_;
166 using Base::u_dependent_;
167
168 private:
169 pinocchio::FrameIndex id_;
170 Motion vref_;
171 pinocchio::ReferenceFrame type_;
172 std::shared_ptr<typename StateMultibody::PinocchioModel>
173 pin_model_;
174};
175
176template <typename _Scalar>
178 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
179
180 typedef _Scalar Scalar;
184 typedef typename MathBase::Matrix6xs Matrix6xs;
185
186 template <template <typename Scalar> class Model>
187 ResidualDataFrameVelocityTpl(Model<Scalar>* const model,
188 DataCollectorAbstract* const data)
189 : Base(model, data) {
190 // Check that proper shared data has been passed
193 if (d == NULL) {
194 throw_pretty(
195 "Invalid argument: the shared data should be derived from "
196 "DataCollectorMultibody");
197 }
198
199 // Avoids data casting at runtime
200 pinocchio = d->pinocchio;
201 }
202 virtual ~ResidualDataFrameVelocityTpl() = default;
203
204 pinocchio::DataTpl<Scalar>* pinocchio;
205 using Base::r;
206 using Base::Ru;
207 using Base::Rx;
208 using Base::shared;
209};
210
211} // namespace crocoddyl
212
213/* --- Details -------------------------------------------------------------- */
214/* --- Details -------------------------------------------------------------- */
215/* --- Details -------------------------------------------------------------- */
216#include "crocoddyl/multibody/residuals/frame-velocity.hxx"
217
218CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
220CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
222
223#endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_VELOCITY_HPP_
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
std::size_t nr_
Residual vector dimension.
void set_reference(const Motion &velocity)
Modify reference velocity.
void set_id(const pinocchio::FrameIndex id)
Modify 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 Jacobians of the frame velocity residual.
ResidualModelFrameVelocityTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Motion &vref, const pinocchio::ReferenceFrame type, const std::size_t nu)
Initialize the frame velocity residual model.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data) override
Create the frame velocity residual data.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
void set_type(const pinocchio::ReferenceFrame type)
Modify reference type of velocity.
const Motion & get_reference() const
Return the reference velocity.
pinocchio::ReferenceFrame get_type() const
Return the reference type of velocity.
ResidualModelFrameVelocityTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Motion &vref, const pinocchio::ReferenceFrame type)
Initialize the frame velocity 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 velocity residual vector.
virtual void print(std::ostream &os) const override
Print relevant information of the frame-velocity residual.
ResidualModelFrameVelocityTpl< NewScalar > cast() const
Cast the frame-velocity residual model to a different scalar type.
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.
DataCollectorAbstract * shared
Shared data allocated by the action model.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.