contacts/contact-point.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_point_hpp__
19 #define __invdyn_contact_point_hpp__
20 
25 
26 namespace tsid {
27 namespace contacts {
28 class ContactPoint : public ContactBase {
29  public:
30  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
31 
42 
43  ContactPoint(const std::string& name, RobotWrapper& robot,
44  const std::string& frameName, ConstRefVector contactNormal,
45  const double frictionCoefficient, const double minNormalForce,
46  const double maxNormalForce);
47 
48  virtual ~ContactPoint() {}
49 
51  virtual unsigned int n_motion() const;
52 
54  virtual unsigned int n_force() const;
55 
56  virtual const ConstraintBase& computeMotionTask(const double t,
57  ConstRefVector q,
58  ConstRefVector v, Data& data);
59 
60  virtual const ConstraintInequality& computeForceTask(const double t,
61  ConstRefVector q,
62  ConstRefVector v,
63  const Data& data);
64 
65  virtual const Matrix& getForceGeneratorMatrix();
66 
67  virtual const ConstraintEquality& computeForceRegularizationTask(
68  const double t, ConstRefVector q, ConstRefVector v, const Data& data);
69 
70  const TaskSE3Equality& getMotionTask() const;
71  const ConstraintBase& getMotionConstraint() const;
72  const ConstraintInequality& getForceConstraint() const;
73  const ConstraintEquality& getForceRegularizationTask() const;
74  double getMotionTaskWeight() const;
75  const Matrix3x& getContactPoints() const;
76 
77  double getNormalForce(ConstRefVector f) const;
78  double getMinNormalForce() const;
79  double getMaxNormalForce() const;
80 
81  const Vector&
82  Kp(); // cannot be const because it set a member variable inside
83  const Vector&
84  Kd(); // cannot be const because it set a member variable inside
85  void Kp(ConstRefVector Kp);
86  void Kd(ConstRefVector Kp);
87 
88  bool setContactNormal(ConstRefVector contactNormal);
89 
90  bool setFrictionCoefficient(const double frictionCoefficient);
91  bool setMinNormalForce(const double minNormalForce);
92  bool setMaxNormalForce(const double maxNormalForce);
93  bool setMotionTaskWeight(const double w);
94  void setReference(const SE3& ref);
95  void setForceReference(ConstRefVector& f_ref);
96  void setRegularizationTaskWeightVector(ConstRefVector& w);
97 
107  void useLocalFrame(bool local_frame);
108 
109  protected:
113 
114  TaskSE3Equality m_motionTask;
115  ConstraintInequality m_forceInequality;
116  ConstraintEquality m_forceRegTask;
118  Vector3 m_fRef;
120  Matrix3x m_contactPoints;
121  Vector m_Kp3, m_Kd3; // gain vectors to be returned by reference
122  double m_mu;
123  double m_fMin;
124  double m_fMax;
128 };
129 } // namespace contacts
130 } // namespace tsid
131 
132 #endif // ifndef __invdyn_contact_6d_hpp__
const Eigen::Ref< const Matrix > ConstRefMatrix
Definition: math/fwd.hpp:51
const Matrix3x & getContactPoints() const
const TaskSE3Equality & getMotionTask() const
virtual const ConstraintInequality & computeForceTask(const double t, ConstRefVector q, ConstRefVector v, const Data &data)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hpp:35
ContactPoint(const std::string &name, RobotWrapper &robot, const std::string &frameName, ConstRefVector contactNormal, const double frictionCoefficient, const double minNormalForce, const double maxNormalForce)
virtual const ConstraintEquality & computeForceRegularizationTask(const double t, ConstRefVector q, ConstRefVector v, const Data &data)
virtual const Matrix & getForceGeneratorMatrix()
data
Definition: setup.in.py:48
Base template of a Contact.
bool setFrictionCoefficient(const double frictionCoefficient)
virtual unsigned int n_force() const
Return the number of force variables.
bool setContactNormal(ConstRefVector contactNormal)
Eigen::Matrix< Scalar, 3, 1 > Vector3
Definition: math/fwd.hpp:40
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstRefMatrix ConstRefMatrix
const ConstraintInequality & getForceConstraint() const
bool setMotionTaskWeight(const double w)
const Eigen::Ref< const Vector > ConstRefVector
Definition: math/fwd.hpp:48
math::ConstraintEquality ConstraintEquality
const std::string & name() const
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
Definition: math/fwd.hpp:42
Wrapper for a robot based on pinocchio.
math::ConstraintInequality ConstraintInequality
const ConstraintBase & getMotionConstraint() const
void setForceReference(ConstRefVector &f_ref)
Eigen::TensorRef< Tensor > ref(Eigen::TensorRef< Tensor > tensor)
virtual const ConstraintBase & computeMotionTask(const double t, ConstRefVector q, ConstRefVector v, Data &data)
Transform3f t
bool setMinNormalForce(const double minNormalForce)
Eigen::Matrix< Scalar, 6, 1 > Vector6
Definition: math/fwd.hpp:41
virtual unsigned int n_motion() const
Return the number of motion constraints.
w
tasks::TaskSE3Equality TaskSE3Equality
const ConstraintEquality & getForceRegularizationTask() const
string frameName
Definition: test_Contact.py:29
void setRegularizationTaskWeightVector(ConstRefVector &w)
void useLocalFrame(bool local_frame)
Specifies if properties of the contact point and motion task are expressed in the local or local worl...
bool setMaxNormalForce(const double maxNormalForce)
double getNormalForce(ConstRefVector f) const
double getMotionTaskWeight() const


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