contact-base.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017 CNRS
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_base_hpp__
19 #define __invdyn_contact_base_hpp__
20 
21 #include "tsid/math/fwd.hpp"
22 #include "tsid/robots/fwd.hpp"
24 
25 namespace tsid {
26 namespace contacts {
27 
31 class ContactBase {
32  public:
33  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
34 
44 
45  ContactBase(const std::string& name, RobotWrapper& robot);
46 
47  virtual ~ContactBase() {}
48 
49  const std::string& name() const;
50 
51  void name(const std::string& name);
52 
54  virtual unsigned int n_motion() const = 0;
55 
57  virtual unsigned int n_force() const = 0;
58 
59  virtual const ConstraintBase& computeMotionTask(const double t,
60  ConstRefVector q,
61  ConstRefVector v,
62  Data& data) = 0;
63 
64  virtual const ConstraintInequality& computeForceTask(const double t,
65  ConstRefVector q,
66  ConstRefVector v,
67  const Data& data) = 0;
68 
69  virtual const Matrix& getForceGeneratorMatrix() = 0;
70 
71  virtual const ConstraintEquality& computeForceRegularizationTask(
72  const double t, ConstRefVector q, ConstRefVector v, const Data& data) = 0;
73 
74  virtual const TaskSE3Equality& getMotionTask() const = 0;
75  virtual const ConstraintBase& getMotionConstraint() const = 0;
76  virtual const ConstraintInequality& getForceConstraint() const = 0;
77  virtual const ConstraintEquality& getForceRegularizationTask() const = 0;
78 
79  virtual double getMinNormalForce() const = 0;
80  virtual double getMaxNormalForce() const = 0;
81  virtual bool setMinNormalForce(const double minNormalForce) = 0;
82  virtual bool setMaxNormalForce(const double maxNormalForce) = 0;
83  virtual double getNormalForce(ConstRefVector f) const = 0;
84  virtual const Matrix3x& getContactPoints() const = 0;
85 
86  protected:
87  std::string m_name;
89  RobotWrapper& m_robot;
90 };
91 
92 } // namespace contacts
93 } // namespace tsid
94 
95 #endif // ifndef __invdyn_contact_base_hpp__
ContactBase(const std::string &name, RobotWrapper &robot)
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
Definition: math/fwd.hpp:36
virtual double getNormalForce(ConstRefVector f) const =0
virtual const Matrix3x & getContactPoints() const =0
virtual const TaskSE3Equality & getMotionTask() const =0
math::ConstRefVector ConstRefVector
virtual const ConstraintEquality & getForceRegularizationTask() const =0
data
Definition: setup.in.py:48
virtual const ConstraintEquality & computeForceRegularizationTask(const double t, ConstRefVector q, ConstRefVector v, const Data &data)=0
virtual const ConstraintInequality & computeForceTask(const double t, ConstRefVector q, ConstRefVector v, const Data &data)=0
Base template of a Contact.
robots::RobotWrapper RobotWrapper
tasks::TaskSE3Equality TaskSE3Equality
const Eigen::Ref< const Vector > ConstRefVector
Definition: math/fwd.hpp:48
virtual const ConstraintBase & getMotionConstraint() const =0
virtual bool setMaxNormalForce(const double maxNormalForce)=0
const std::string & name() const
RobotWrapper & m_robot
Reference on the robot model.
virtual const ConstraintBase & computeMotionTask(const double t, ConstRefVector q, ConstRefVector v, Data &data)=0
virtual bool setMinNormalForce(const double minNormalForce)=0
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
Definition: math/fwd.hpp:42
Wrapper for a robot based on pinocchio.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase ConstraintBase
math::ConstraintInequality ConstraintInequality
Transform3f t
virtual double getMaxNormalForce() const =0
virtual double getMinNormalForce() const =0
virtual unsigned int n_force() const =0
Return the number of force variables.
math::ConstraintEquality ConstraintEquality
virtual const Matrix & getForceGeneratorMatrix()=0
Abstract class representing a linear equality/inequality constraint. Equality constraints are represe...
virtual const ConstraintInequality & getForceConstraint() const =0
virtual unsigned int n_motion() const =0
Return the number of motion constraints.


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