contacts/contact-6d.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017 CNRS, NYU, MPI Tübingen
3 //
4 // This file is part of tsid
5 // tsid is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 // tsid is distributed in the hope that it will be
10 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12 // General Lesser Public License for more details. You should have
13 // received a copy of the GNU Lesser General Public License along with
14 // tsid If not, see
15 // <http://www.gnu.org/licenses/>.
16 //
17 
18 #ifndef __invdyn_contact_6d_hpp__
19 #define __invdyn_contact_6d_hpp__
20 
21 #include "tsid/deprecated.hh"
26 
27 namespace tsid {
28 namespace contacts {
29 class Contact6d : public ContactBase {
30  public:
31  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
32 
43 
44  Contact6d(const std::string& name, RobotWrapper& robot,
45  const std::string& frameName, ConstRefMatrix contactPoints,
46  ConstRefVector contactNormal, const double frictionCoefficient,
47  const double minNormalForce, const double maxNormalForce);
48 
49  TSID_DEPRECATED Contact6d(const std::string& name, RobotWrapper& robot,
50  const std::string& frameName,
51  ConstRefMatrix contactPoints,
52  ConstRefVector contactNormal,
53  const double frictionCoefficient,
54  const double minNormalForce,
55  const double maxNormalForce,
56  const double forceRegWeight);
57 
58  virtual ~Contact6d() {}
59 
61  virtual unsigned int n_motion() const;
62 
64  virtual unsigned int n_force() const;
65 
66  virtual const ConstraintBase& computeMotionTask(const double t,
67  ConstRefVector q,
68  ConstRefVector v, Data& data);
69 
70  virtual const ConstraintInequality& computeForceTask(const double t,
71  ConstRefVector q,
72  ConstRefVector v,
73  const Data& data);
74 
75  virtual const Matrix& getForceGeneratorMatrix();
76 
77  virtual const ConstraintEquality& computeForceRegularizationTask(
78  const double t, ConstRefVector q, ConstRefVector v, const Data& data);
79 
80  const TaskSE3Equality& getMotionTask() const;
81  const ConstraintBase& getMotionConstraint() const;
82  const ConstraintInequality& getForceConstraint() const;
83  const ConstraintEquality& getForceRegularizationTask() const;
84 
85  double getNormalForce(ConstRefVector f) const;
86  double getMinNormalForce() const;
87  double getMaxNormalForce() const;
88  const Matrix3x& getContactPoints() const;
89 
90  const Vector& Kp() const;
91  const Vector& Kd() const;
92  void Kp(ConstRefVector Kp);
93  void Kd(ConstRefVector Kp);
94 
95  bool setContactPoints(ConstRefMatrix contactPoints);
96  bool setContactNormal(ConstRefVector contactNormal);
97 
98  bool setFrictionCoefficient(const double frictionCoefficient);
99  bool setMinNormalForce(const double minNormalForce);
100  bool setMaxNormalForce(const double maxNormalForce);
101  void setReference(const SE3& ref);
102  void setForceReference(ConstRefVector& f_ref);
103  void setRegularizationTaskWeightVector(ConstRefVector& w);
104 
105  private:
106  void init();
107 
108  protected:
112 
113  TaskSE3Equality m_motionTask;
114  ConstraintInequality m_forceInequality;
115  ConstraintEquality m_forceRegTask;
116  Matrix3x m_contactPoints;
118  Vector6 m_fRef;
120  double m_mu;
121  double m_fMin;
122  double m_fMax;
124 };
125 } // namespace contacts
126 } // namespace tsid
127 
128 #endif // ifndef __invdyn_contact_6d_hpp__
const Eigen::Ref< const Matrix > ConstRefMatrix
Definition: math/fwd.hpp:51
const ConstraintInequality & getForceConstraint() const
math::ConstraintInequality ConstraintInequality
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hpp:35
double getNormalForce(ConstRefVector f) const
virtual unsigned int n_motion() const
Return the number of motion constraints.
data
Definition: setup.in.py:48
const TaskSE3Equality & getMotionTask() const
const ConstraintEquality & getForceRegularizationTask() const
Base template of a Contact.
virtual unsigned int n_force() const
Return the number of force variables.
const ConstraintBase & getMotionConstraint() const
Eigen::Matrix< Scalar, 3, 1 > Vector3
Definition: math/fwd.hpp:40
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstRefMatrix ConstRefMatrix
void setRegularizationTaskWeightVector(ConstRefVector &w)
math::ConstRefVector ConstRefVector
bool setContactPoints(ConstRefMatrix contactPoints)
virtual const ConstraintInequality & computeForceTask(const double t, ConstRefVector q, ConstRefVector v, const Data &data)
void setForceReference(ConstRefVector &f_ref)
Contact6d(const std::string &name, RobotWrapper &robot, const std::string &frameName, ConstRefMatrix contactPoints, ConstRefVector contactNormal, const double frictionCoefficient, const double minNormalForce, const double maxNormalForce)
const Eigen::Ref< const Vector > ConstRefVector
Definition: math/fwd.hpp:48
ConstraintInequality m_forceInequality
const Matrix3x & getContactPoints() const
const std::string & name() const
math::ConstraintEquality ConstraintEquality
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
Definition: math/fwd.hpp:42
Wrapper for a robot based on pinocchio.
virtual const ConstraintEquality & computeForceRegularizationTask(const double t, ConstRefVector q, ConstRefVector v, const Data &data)
Eigen::TensorRef< Tensor > ref(Eigen::TensorRef< Tensor > tensor)
bool setMaxNormalForce(const double maxNormalForce)
Transform3f t
Eigen::Matrix< Scalar, 6, 1 > Vector6
Definition: math/fwd.hpp:41
bool setFrictionCoefficient(const double frictionCoefficient)
virtual const ConstraintBase & computeMotionTask(const double t, ConstRefVector q, ConstRefVector v, Data &data)
virtual const Matrix & getForceGeneratorMatrix()
tasks::TaskSE3Equality TaskSE3Equality
w
bool setMinNormalForce(const double minNormalForce)
bool setContactNormal(ConstRefVector contactNormal)
string frameName
Definition: test_Contact.py:29


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:51