Crocoddyl
 
Loading...
Searching...
No Matches
contact-1d.hpp
1
2// BSD 3-Clause License
3//
4// Copyright (C) 2020-2023, 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_CONTACTS_CONTACT_1D_HPP_
11#define CROCODDYL_MULTIBODY_CONTACTS_CONTACT_1D_HPP_
12
13#include <pinocchio/algorithm/frames.hpp>
14#include <pinocchio/algorithm/kinematics-derivatives.hpp>
15#include <pinocchio/multibody/data.hpp>
16#include <pinocchio/spatial/motion.hpp>
17
18#include "crocoddyl/core/utils/exception.hpp"
19#include "crocoddyl/multibody/contact-base.hpp"
20#include "crocoddyl/multibody/fwd.hpp"
21
22namespace crocoddyl {
23
24template <typename _Scalar>
26 public:
27 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
28
29 typedef _Scalar Scalar;
35 typedef typename MathBase::Vector2s Vector2s;
36 typedef typename MathBase::Vector3s Vector3s;
37 typedef typename MathBase::VectorXs VectorXs;
38 typedef typename MathBase::Matrix3s Matrix3s;
39
56 ContactModel1DTpl(std::shared_ptr<StateMultibody> state,
57 const pinocchio::FrameIndex id, const Scalar xref,
58 const pinocchio::ReferenceFrame type,
59 const Matrix3s& rotation, const std::size_t nu,
60 const Vector2s& gains = Vector2s::Zero());
61
77 ContactModel1DTpl(std::shared_ptr<StateMultibody> state,
78 const pinocchio::FrameIndex id, const Scalar xref,
79 const pinocchio::ReferenceFrame type,
80 const Vector2s& gains = Vector2s::Zero());
81
82 DEPRECATED(
83 "Use constructor that passes the type type of contact, this assumes is "
84 "pinocchio::LOCAL",
85 ContactModel1DTpl(std::shared_ptr<StateMultibody> state,
86 const pinocchio::FrameIndex id, const Scalar xref,
87 const std::size_t nu,
88 const Vector2s& gains = Vector2s::Zero());)
89 DEPRECATED(
90 "Use constructor that passes the type type of contact, this assumes is "
91 "pinocchio::LOCAL",
92 ContactModel1DTpl(std::shared_ptr<StateMultibody> state,
93 const pinocchio::FrameIndex id, const Scalar xref,
94 const Vector2s& gains = Vector2s::Zero());)
95 virtual ~ContactModel1DTpl();
96
104 virtual void calc(const std::shared_ptr<ContactDataAbstract>& data,
105 const Eigen::Ref<const VectorXs>& x);
106
114 virtual void calcDiff(const std::shared_ptr<ContactDataAbstract>& data,
115 const Eigen::Ref<const VectorXs>& x);
116
123 virtual void updateForce(const std::shared_ptr<ContactDataAbstract>& data,
124 const VectorXs& force);
125
129 virtual std::shared_ptr<ContactDataAbstract> createData(
130 pinocchio::DataTpl<Scalar>* const data);
131
135 const Scalar get_reference() const;
136
140 const Vector2s& get_gains() const;
141
145 const Matrix3s& get_axis_rotation() const;
146
150 void set_reference(const Scalar reference);
151
155 void set_axis_rotation(const Matrix3s& rotation);
156
162 virtual void print(std::ostream& os) const;
163
164 protected:
165 using Base::id_;
166 using Base::nc_;
167 using Base::nu_;
168 using Base::state_;
169 using Base::type_;
170
171 private:
172 Scalar xref_;
173 Matrix3s Raxis_;
174 Vector2s gains_;
175};
176
177template <typename _Scalar>
178struct ContactData1DTpl : public ContactDataAbstractTpl<_Scalar> {
179 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
180
181 typedef _Scalar Scalar;
184 typedef typename MathBase::Matrix2s Matrix2s;
185 typedef typename MathBase::Matrix3s Matrix3s;
186 typedef typename MathBase::Matrix3xs Matrix3xs;
187 typedef typename MathBase::Matrix6xs Matrix6xs;
188 typedef typename MathBase::Vector3s Vector3s;
189 typedef typename pinocchio::MotionTpl<Scalar> Motion;
190 typedef typename pinocchio::ForceTpl<Scalar> Force;
191
192 template <template <typename Scalar> class Model>
193 ContactData1DTpl(Model<Scalar>* const model,
194 pinocchio::DataTpl<Scalar>* const data)
195 : Base(model, data),
196 v(Motion::Zero()),
197 f_local(Force::Zero()),
198 da0_local_dx(3, model->get_state()->get_ndx()),
199 fJf(6, model->get_state()->get_nv()),
200 v_partial_dq(6, model->get_state()->get_nv()),
201 a_partial_dq(6, model->get_state()->get_nv()),
202 a_partial_dv(6, model->get_state()->get_nv()),
203 a_partial_da(6, model->get_state()->get_nv()),
204 fXjdv_dq(6, model->get_state()->get_nv()),
205 fXjda_dq(6, model->get_state()->get_nv()),
206 fXjda_dv(6, model->get_state()->get_nv()),
207 fJf_df(3, model->get_state()->get_nv()) {
208 frame = model->get_id();
209 jMf = model->get_state()->get_pinocchio()->frames[frame].placement;
210 fXj = jMf.inverse().toActionMatrix();
211 a0_local.setZero();
212 dp.setZero();
213 dp_local.setZero();
214 da0_local_dx.setZero();
215 fJf.setZero();
216 v_partial_dq.setZero();
217 a_partial_dq.setZero();
218 a_partial_dv.setZero();
219 a_partial_da.setZero();
220 vv_skew.setZero();
221 vw_skew.setZero();
222 a0_skew.setZero();
223 a0_world_skew.setZero();
224 dp_skew.setZero();
225 f_skew.setZero();
226 fXjdv_dq.setZero();
227 fXjda_dq.setZero();
228 fXjda_dv.setZero();
229 oRf.setZero();
230 fJf_df.setZero();
231 }
232
233 using Base::a0;
234 using Base::da0_dx;
235 using Base::df_du;
236 using Base::df_dx;
237 using Base::f;
238 using Base::frame;
239 using Base::fXj;
240 using Base::Jc;
241 using Base::jMf;
242 using Base::pinocchio;
243
244 Motion v;
245 Vector3s a0_local;
246 Vector3s dp;
247 Vector3s dp_local;
248 Force f_local;
249 Matrix3xs da0_local_dx;
250 Matrix6xs fJf;
251 Matrix6xs v_partial_dq;
252 Matrix6xs a_partial_dq;
253 Matrix6xs a_partial_dv;
254 Matrix6xs a_partial_da;
255 Matrix3s vv_skew;
256 Matrix3s vw_skew;
257 Matrix3s a0_skew;
258 Matrix3s a0_world_skew;
259 Matrix3s dp_skew;
260 Matrix3s f_skew;
261 Matrix6xs fXjdv_dq;
262 Matrix6xs fXjda_dq;
263 Matrix6xs fXjda_dv;
264 Matrix2s oRf;
265 Matrix3xs fJf_df;
266};
267
268} // namespace crocoddyl
269
270/* --- Details -------------------------------------------------------------- */
271/* --- Details -------------------------------------------------------------- */
272/* --- Details -------------------------------------------------------------- */
273#include "crocoddyl/multibody/contacts/contact-1d.hxx"
274
275#endif // CROCODDYL_MULTIBODY_CONTACTS_CONTACT_1D_HPP_
const Vector2s & get_gains() const
Create the 1d contact data.
ContactModel1DTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Scalar xref, const pinocchio::ReferenceFrame type, const Matrix3s &rotation, const std::size_t nu, const Vector2s &gains=Vector2s::Zero())
Initialize the 1d contact model.
virtual void calcDiff(const std::shared_ptr< ContactDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the derivatives of the 1d contact holonomic constraint.
virtual void print(std::ostream &os) const
Print relevant information of the 1d contact model.
const Matrix3s & get_axis_rotation() const
Return the rotation of the reference frames's z axis.
void set_reference(const Scalar reference)
Modify the reference frame translation.
void set_axis_rotation(const Matrix3s &rotation)
Modify the rotation of the reference frames's z axis.
const Scalar get_reference() const
Return the reference frame translation.
virtual void updateForce(const std::shared_ptr< ContactDataAbstract > &data, const VectorXs &force)
Convert the force into a stack of spatial forces.
ContactModel1DTpl(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Scalar xref, const pinocchio::ReferenceFrame type, const Vector2s &gains=Vector2s::Zero())
Initialize the 1d contact model.
virtual void calc(const std::shared_ptr< ContactDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the 1d contact Jacobian and drift.
virtual std::shared_ptr< ContactDataAbstract > createData(pinocchio::DataTpl< Scalar > *const data)
Create the 1d contact data.
pinocchio::ReferenceFrame type_
Type of contact.
pinocchio::FrameIndex id_
Reference frame id of the contact.
State multibody representation.
Definition multibody.hpp:35
PinocchioData * pinocchio
Pinocchio data.
pinocchio::FrameIndex frame
Frame index of the contact frame.
SE3 jMf
Local frame placement of the contact frame.
MatrixXs Jc
Contact Jacobian.
Force f
Contact force expressed in the coordinate defined by type.