dyna_com.hpp
Go to the documentation of this file.
1 
10 #ifndef AIG_DYNACOM
11 #define AIG_DYNACOM
12 
13 // clang-format off
14 #include <Eigen/Dense>
15 #include "pinocchio/fwd.hpp"
16 #include "pinocchio/multibody/data.hpp"
17 #include "pinocchio/multibody/model.hpp"
18 #include "pinocchio/spatial/se3.hpp"
19 #include <map>
20 #include <memory>
21 #include "aig/contact6d.hpp"
22 // clang-format on
23 
24 // @TODO: Separate the DynaCom in a new repository.
25 // @TODO: add abstract class contact and new implementation of it contactPoint.
26 // @TODO: implement method copy of contacts to be able to duplicate them easily.
27 // @TODO: In the getters uni_A, fria_A, uni_b, fri_b return only the active
28 // block.
29 // @TODO: change internaly the system of names by ids.
30 
31 namespace aig {
32 
34  public:
39  std::string urdf = "";
40 
41  friend std::ostream &operator<<(std::ostream &out,
42  const DynaCoMSettings &obj) {
43  out << "DynaCoMSettings:\n";
44  out << " urdf: " << obj.urdf << std::endl;
45  return out;
46  }
47 
48  friend bool operator==(const DynaCoMSettings &lhs,
49  const DynaCoMSettings &rhs) {
50  bool test = true;
51  test &= lhs.urdf == rhs.urdf;
52  return test;
53  }
54 };
55 
56 class DynaCoM {
57  public:
58  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
59  private:
60  DynaCoMSettings settings_;
61  Eigen::Matrix2d S_;
62  pinocchio::Model model_;
63  pinocchio::Data data_;
64  double mass_;
65  double inf_ = std::numeric_limits<double>::infinity();
66 
67  // Lists of contacts
68  // std::vector< std::shared_ptr<Contact6D> > known_contact6ds_;
69  std::map<std::string, std::shared_ptr<Contact6D>> known_contact6ds_;
70  std::vector<std::string> active_contact6ds_;
71 
72  // QP Matrices
73  Eigen::MatrixXd unilaterality_A_;
74  Eigen::VectorXd unilaterality_b_;
75  Eigen::MatrixXd friction_A_;
76  Eigen::VectorXd friction_b_;
77  Eigen::VectorXd regularization_A_;
78  Eigen::VectorXd regularization_b_;
79  Eigen::Matrix<double, 6, -1> newton_euler_A_;
80  Eigen::Matrix<double, 6, 1> newton_euler_b_;
81 
82  // variables for QP problem with proxsuite formulation
83  // Eigen::MatrixXd H_, , A_;
84  // Eigen::VectorXd g_, u_, l_;
85  // Eigen::Matrix<double, 6, 1> b_;
86 
87  // variables for QP problem with eiquadprog formulation
88  Eigen::MatrixXd G_; // matrix for quadratic cost
89  Eigen::VectorXd g0_; // linear part of the cost function
90  Eigen::MatrixXd CE_, CI_, C_; // constraints matrix
91  Eigen::VectorXd ce0_, ci0_; // constraints vector
92 
93  // variables for QP problem
94  Eigen::VectorXd F_;
95  Eigen::VectorXi activeSet_;
96  size_t activeSetSize_;
97 
98  size_t cols_, uni_rows_, fri_rows_;
99  // active sizes:
100  size_t uni_i_, fri_i_, j_;
101 
102  // Internal variables:
103  Eigen::Vector3d groundCoMForce_, groundCoMTorque_, CoPTorque_, weight_;
104  Eigen::Vector3d acom_;
105  Eigen::Vector2d cop_;
106  Eigen::Vector3d dL_;
107  Eigen::Vector3d L_;
108  Eigen::Vector2d n_;
109  std::vector<std::string>::iterator activeID_;
110  std::map<std::string, std::shared_ptr<aig::Contact6D>>::iterator knownID_;
111 
112  // for the CoP wrench
113  pinocchio::SE3 oMso_, soMs_;
114  Eigen::Matrix<double, 6, 6> Sz_, oXso_, soXs_;
115 
116  void addSizes(const std::shared_ptr<Contact6D> &contact);
117  void removeSizes(const std::shared_ptr<Contact6D> &contact);
118  void resizeMatrices();
119  void buildMatrices(const Eigen::Vector3d &groundCoMForce,
120  const Eigen::Vector3d &groundCoMTorque,
121  const Eigen::Vector3d &CoM);
122  void solveQP();
123  void distribute();
124 
125  const Eigen::Matrix<double, 6, 6> toWorldCoPWrench(pinocchio::SE3 pose);
126 
127  public:
128  DynaCoM();
129  DynaCoM(const DynaCoMSettings settings);
130  void initialize(const DynaCoMSettings settings);
131 
132  void computeDynamics(const Eigen::VectorXd &posture,
133  const Eigen::VectorXd &velocity,
134  const Eigen::VectorXd &acceleration,
135  const Eigen::Matrix<double, 6, 1> &externalWrench =
136  Eigen::Matrix<double, 6, 1>::Zero(),
137  bool flatHorizontalGround = true);
138 
139  void computeNL(const double &w, const Eigen::VectorXd &posture,
140  const Eigen::VectorXd &velocity,
141  const Eigen::VectorXd &acceleration,
142  const Eigen::Matrix<double, 6, 1> &externalWrench =
143  Eigen::Matrix<double, 6, 1>::Zero(),
144  bool flatHorizontalGround = true);
145 
146  void computeNL(const double &w);
147 
148  void addContact6d(const std::shared_ptr<Contact6D> &contact,
149  const std::string &name, const bool active = true);
150  void removeContact6d(const std::string &name);
151 
152  void activateContact6d(const std::string &name);
153  void deactivateContact6d(const std::string &name);
154 
155  void distributeForce(const Eigen::Vector3d &groundCoMForce,
156  const Eigen::Vector3d &groundCoMTorque,
157  const Eigen::Vector3d &CoM);
158 
159  // GETTERS
161  const Eigen::Vector3d &getAMVariation() { return dL_; }
162  const Eigen::Vector3d &getCoM() { return data_.com[0]; }
163  const Eigen::Vector3d &getVCoM() { return data_.vcom[0]; }
164  const Eigen::Vector3d &getACoM() { return acom_; }
165  const Eigen::Vector3d &getAM() { return L_; }
166  const Eigen::Vector2d &getCoP() { return cop_; }
167  const Eigen::Vector2d &getNL() { return n_; }
168  const Eigen::Vector3d &getGroundCoMForce() { return groundCoMForce_; }
169  const Eigen::Vector3d &getGroundCoMTorque() { return groundCoMTorque_; }
170  const std::vector<std::string> &getActiveContacts() {
171  return active_contact6ds_;
172  }
173  const std::shared_ptr<Contact6D> &getContact(std::string name) {
174  return known_contact6ds_[name];
175  }
176  const DynaCoMSettings &getSettings() { return settings_; }
177  const pinocchio::Model &getModel() { return model_; }
178  const pinocchio::Data &getData() { return data_; }
179 
180  const Eigen::MatrixXd uni_A() {
181  return unilaterality_A_.block(0, 0, uni_i_, j_);
182  }
183  const Eigen::VectorXd uni_b() { return unilaterality_b_.segment(0, j_); }
184  const Eigen::MatrixXd fri_A() { return friction_A_.block(0, 0, fri_i_, j_); }
185  const Eigen::VectorXd fri_b() { return friction_b_.segment(0, j_); }
186  const Eigen::VectorXd reg_A() { return regularization_A_.segment(0, j_); }
187  const Eigen::VectorXd reg_b() { return regularization_b_.segment(0, j_); }
188  const Eigen::Matrix<double, 6, -1> NE_A() {
189  return newton_euler_A_.block(0, 0, 6, j_);
190  }
191  const Eigen::Matrix<double, 6, 1> &NE_b() { return newton_euler_b_; }
192  const Eigen::VectorXd &allForces() { return F_; }
193 };
194 
195 } // namespace aig
196 
197 #endif // AIG_DYNACOM
Definition: dyna_com.hpp:56
void addContact6d(const std::shared_ptr< Contact6D > &contact, const std::string &name, const bool active=true)
Definition: dyna_com.cpp:164
void activateContact6d(const std::string &name)
Definition: dyna_com.cpp:211
const Eigen::VectorXd uni_b()
Definition: dyna_com.hpp:183
const pinocchio::Model & getModel()
Definition: dyna_com.hpp:177
void computeDynamics(const Eigen::VectorXd &posture, const Eigen::VectorXd &velocity, const Eigen::VectorXd &acceleration, const Eigen::Matrix< double, 6, 1 > &externalWrench=Eigen::Matrix< double, 6, 1 >::Zero(), bool flatHorizontalGround=true)
Definition: dyna_com.cpp:86
const std::vector< std::string > & getActiveContacts()
Definition: dyna_com.hpp:170
const Eigen::Vector3d & getCoM()
Definition: dyna_com.hpp:162
const pinocchio::Data & getData()
Definition: dyna_com.hpp:178
const Eigen::Vector2d & getNL()
Definition: dyna_com.hpp:167
const Eigen::Vector2d & getCoP()
Definition: dyna_com.hpp:166
void computeNL(const double &w, const Eigen::VectorXd &posture, const Eigen::VectorXd &velocity, const Eigen::VectorXd &acceleration, const Eigen::Matrix< double, 6, 1 > &externalWrench=Eigen::Matrix< double, 6, 1 >::Zero(), bool flatHorizontalGround=true)
Definition: dyna_com.cpp:143
const Eigen::Vector3d & getVCoM()
Definition: dyna_com.hpp:163
const Eigen::MatrixXd uni_A()
Definition: dyna_com.hpp:180
const Eigen::MatrixXd fri_A()
Definition: dyna_com.hpp:184
const Eigen::Vector3d & getAM()
Definition: dyna_com.hpp:165
void deactivateContact6d(const std::string &name)
Definition: dyna_com.cpp:229
void removeContact6d(const std::string &name)
Definition: dyna_com.cpp:176
const std::shared_ptr< Contact6D > & getContact(std::string name)
Definition: dyna_com.hpp:173
DynaCoM()
Definition: dyna_com.cpp:21
const DynaCoMSettings & getSettings()
Definition: dyna_com.hpp:176
void initialize(const DynaCoMSettings settings)
Definition: dyna_com.cpp:24
const Eigen::Vector3d & getGroundCoMForce()
Definition: dyna_com.hpp:168
const Eigen::VectorXd fri_b()
Definition: dyna_com.hpp:185
const Eigen::VectorXd & allForces()
Definition: dyna_com.hpp:192
const Eigen::Vector3d & getGroundCoMTorque()
Definition: dyna_com.hpp:169
const Eigen::Vector3d & getAMVariation()
Please call computeDynamics first.
Definition: dyna_com.hpp:161
const Eigen::VectorXd reg_A()
Definition: dyna_com.hpp:186
const Eigen::Matrix< double, 6, 1 > & NE_b()
Definition: dyna_com.hpp:191
const Eigen::Vector3d & getACoM()
Definition: dyna_com.hpp:164
void distributeForce(const Eigen::Vector3d &groundCoMForce, const Eigen::Vector3d &groundCoMTorque, const Eigen::Vector3d &CoM)
Definition: dyna_com.cpp:392
const Eigen::Matrix< double, 6, -1 > NE_A()
Definition: dyna_com.hpp:188
const Eigen::VectorXd reg_b()
Definition: dyna_com.hpp:187
Class to perform inverse geometry on a biped robot.
Definition: arm_ig.hpp:18
Definition: dyna_com.hpp:33
std::string urdf
This must contain either a valid path to the urdf file or the content of this file in a string.
Definition: dyna_com.hpp:39
friend bool operator==(const DynaCoMSettings &lhs, const DynaCoMSettings &rhs)
Definition: dyna_com.hpp:48
friend std::ostream & operator<<(std::ostream &out, const DynaCoMSettings &obj)
Definition: dyna_com.hpp:41