1 // =============================================================================
2 // PROJECT CHRONO - http://projectchrono.org
3 //
4 // Copyright (c) 2014 projectchrono.org
5 // All rights reserved.
6 //
7 // Use of this source code is governed by a BSD-style license that can be found
8 // in the LICENSE file at the top level of the distribution and at
9 // http://projectchrono.org/license-chrono.txt.
10 //
11 // =============================================================================
12 // Authors: Alessandro Tasora, Radu Serban
13 // =============================================================================
14 
15 #ifndef CHSYSTEMDESCRIPTOR_H
16 #define CHSYSTEMDESCRIPTOR_H
17 
18 #include <vector>
19 
20 #include "chrono/solver/ChConstraint.h"
21 #include "chrono/solver/ChKblock.h"
22 #include "chrono/solver/ChVariables.h"
23 
24 namespace chrono {
25 
26 /// Base class for collecting objects inherited from ChConstraint,
27 /// ChVariables and optionally ChKblock. These objects
28 /// can be used to define a sparse representation of the system.
29 /// This collector is important because it contains all the required
30 /// information that is sent to a solver (usually a VI/CCP solver, or
31 /// as a subcase, a linear solver).\n
32 /// The problem is described by a variational inequality VI(Z*x-d,K):\n
33 /// The matrix \f$Z\f$ that represents the problem has this form:
34 /// <pre>
35 ///  | H -Cq'|*|q|- | f|= |0|
36 ///  | Cq -E | |l|  |-b|  |c|
37 /// </pre>
38 /// with \f$Y \ni \mathbb{l}  \perp \mathbb{c} \in N_y\f$ \n
39 /// where \f$N_y\f$ is the normal cone to \f$Y\f$ \n
40 /// By flipping the sign of \f$l_i\f$, the matrix \f$Z\f$ can be symmetric (but in general non positive definite)
41 /// <pre>
42 /// | H  Cq'|*| q|-| f|=|0|
43 /// | Cq  E | |-l| |-b| |c|
44 /// </pre>
45 ///
46 /// * Linear Problem: \f$ \forall i \,Y_i = \mathbb{R}, N_{y_{i}} = 0\f$ (e.g. all bilateral)
47 /// * Linear Complementarity Problem (LCP): \f$ 0\le c \perp l\ge0 \f$ (i.e. \f$Y_i = \mathbb{R}^+\f$)
48 /// * Cone Complementarity Problem (CCP): \f$Y \ni \mathbb{l}  \perp \mathbb{c} \in N_y\f$ (\f$Y_i\f$ are friction
49 /// cones)
50 ///
51 /// *Notes*
52 /// 1. most often you call ConvertToMatrixForm() right after a dynamic simulation step,
53 ///    in order to get the system matrices updated to the last timestep;
54 /// 2. when using Anitescu default stepper, the 'f' vector contains forces*timestep = F*dt
55 /// 3. when using Anitescu default stepper, 'q' represents the 'delta speed',
56 /// 4. when using Anitescu default stepper, 'b' represents the dt/phi stabilization term.
57 /// 5. usually, H = M, the mass matrix, but in some cases, ex. when using
58 ///         implicit integrators, objects inherited from ChKblock can be added
59 ///         too, hence H could be H=a*M+b*K+c*R (but not all solvers handle ChKblock!)
60 ///
61 /// All solvers require that the description of the system
62 /// is passed by means of a ChSystemDescriptor object
63 /// that holds a list of all the constraints, variables, masses, known terms
64 ///	(ex.forces) under the form of ChVariables, ChConstraints and ChKblock.
65 ///
66 /// In this default implementation, the ChSystemDescriptor
67 /// simply holds a vector of pointers to ChVariables
68 /// or to ChConstraints, but more advanced implementations (ex. for
69 /// supporting parallel GPU solvers) could store constraints
70 /// and variables structures with other, more efficient data schemes.
71 
72 class ChApi ChSystemDescriptor {
73   protected:
74     std::vector<ChConstraint*> vconstraints;  ///< list of pointers to all the ChConstraint in the current Chrono system
75     std::vector<ChVariables*> vvariables;     ///< list of pointers to all the ChVariables in the current Chrono system
76     std::vector<ChKblock*> vstiffness;        ///< list of pointers to all the ChKblock in the current Chrono system
77 
78     double c_a;  // coefficient form M mass matrices in vvariables
79 
80   private:
81     int n_q;            ///< number of active variables
82     int n_c;            ///< number of active constraints
83     bool freeze_count;  ///< for optimization: avoid to re-count the number of active variables and constraints
84 
85   public:
86     /// Constructor
87     ChSystemDescriptor();
88 
89     /// Destructor
90     virtual ~ChSystemDescriptor();
91 
92     // DATA MANAGEMENT FUNCTIONS
93 
94     /// Access the vector of constraints
GetConstraintsList()95     std::vector<ChConstraint*>& GetConstraintsList() { return vconstraints; }
96 
97     /// Access the vector of variables
GetVariablesList()98     std::vector<ChVariables*>& GetVariablesList() { return vvariables; }
99 
100     /// Access the vector of stiffness matrix blocks
GetKblocksList()101     std::vector<ChKblock*>& GetKblocksList() { return vstiffness; }
102 
103     /// Begin insertion of items
BeginInsertion()104     virtual void BeginInsertion() {
105         vconstraints.clear();
106         vvariables.clear();
107         vstiffness.clear();
108     }
109 
110     /// Insert reference to a ChConstraint object
InsertConstraint(ChConstraint * mc)111     virtual void InsertConstraint(ChConstraint* mc) { vconstraints.push_back(mc); }
112 
113     /// Insert reference to a ChVariables object
InsertVariables(ChVariables * mv)114     virtual void InsertVariables(ChVariables* mv) { vvariables.push_back(mv); }
115 
116     /// Insert reference to a ChKblock object (a piece of matrix)
InsertKblock(ChKblock * mk)117     virtual void InsertKblock(ChKblock* mk) { vstiffness.push_back(mk); }
118 
119     /// End insertion of items.
120     /// A derived class should always call UpdateCountsAndOffsets.
EndInsertion()121     virtual void EndInsertion() { UpdateCountsAndOffsets(); }
122 
123     /// Count & returns the scalar variables in the system (excluding ChVariable objects
124     /// that have  IsActive() as false). Note: the number of scalar variables is not necessarily
125     /// the number of inserted ChVariable objects, some could be inactive.
126     /// Note: this function also updates the offsets of all variables
127     /// in 'q' global vector (see GetOffset() in ChVariables).
128     virtual int CountActiveVariables();
129 
130     /// Count & returns the scalar constraints in the system (excluding ChConstraint objects
131     /// that have  IsActive() as false).
132     /// Note: this function also updates the offsets of all constraints
133     /// in 'l' global vector (see GetOffset() in ChConstraint).
134     virtual int CountActiveConstraints();
135 
136     /// Updates counts of scalar variables and scalar constraints,
137     /// if you added/removed some item or if you switched some active state,
138     /// otherwise CountActiveVariables() and CountActiveConstraints() might fail.
139     virtual void UpdateCountsAndOffsets();
140 
141     /// Sets the c_a coefficient (default=1) used for scaling the M masses of the vvariables
142     /// when performing ShurComplementProduct(), SystemProduct(), ConvertToMatrixForm(),
SetMassFactor(const double mc_a)143     virtual void SetMassFactor(const double mc_a) { c_a = mc_a; }
144 
145     /// Gets the c_a coefficient (default=1) used for scaling the M masses of the vvariables
146     /// when performing ShurComplementProduct(), SystemProduct(), ConvertToMatrixForm(),
GetMassFactor()147     virtual double GetMassFactor() { return c_a; }
148 
149     // DATA <-> MATH.VECTORS FUNCTIONS
150 
151     /// Get a vector with all the 'fb' known terms ('forces'etc.) associated to all variables,
152     /// ordered into a column vector. The column vector must be passed as a ChMatrix<>
153     /// object, which will be automatically reset and resized to the proper length if necessary.
154     virtual int BuildFbVector(ChVectorDynamic<>& Fvector  ///< system-level vector 'f'
155     );
156 
157     /// Get a vector with all the 'bi' known terms ('constraint residuals' etc.) associated to all constraints,
158     /// ordered into a column vector. The column vector must be passed as a ChMatrix<>
159     /// object, which will be automatically reset and resized to the proper length if necessary.
160     virtual int BuildBiVector(ChVectorDynamic<>& Bvector  ///< system-level vector 'b'
161     );
162 
163     /// Get the d vector = {f; -b} with all the 'fb' and 'bi' known terms, as in  Z*y-d
164     /// (it is the concatenation of BuildFbVector and BuildBiVector) The column vector must be passed as a ChMatrix<>
165     /// object, which will be automatically reset and resized to the proper length if necessary.
166     virtual int BuildDiVector(ChVectorDynamic<>& Dvector  ///< system-level vector {f;-b}
167     );
168 
169     /// Get the D diagonal of the Z system matrix, as a single column vector (it includes all the diagonal
170     /// masses of M, and all the diagonal E (-cfm) terms).
171     /// The Diagonal_vect must already have the size of n. of unknowns, otherwise it will be resized if necessary).
172     virtual int BuildDiagonalVector(
173         ChVectorDynamic<>& Diagonal_vect  ///< system-level vector of terms on M and E diagonal
174     );
175 
176     /// Using this function, one may get a vector with all the variables 'q'
177     /// ordered into a column vector. The column vector must be passed as a ChMatrix<>
178     /// object, which will be automatically reset and resized to the proper length if necessary
179     /// (but if you are sure that the vector has already the proper size, you can optimize
180     /// the performance a bit by setting resize_vector as false).
181     /// \return  the number of scalar variables (i.e. the rows of the column vector).
182     virtual int FromVariablesToVector(ChVectorDynamic<>& mvector,  ///< system-level vector 'q'
183                                       bool resize_vector = true    ///< if true, resize vector as necessary
184     );
185 
186     /// Using this function, one may go in the opposite direction of the FromVariablesToVector()
187     /// function, i.e. one gives a vector with all the variables 'q' ordered into a column vector, and
188     /// the variables objects are updated according to these values.
189     /// NOTE!!! differently from  FromVariablesToVector(), which always works, this
190     /// function will fail if mvector does not match the amount and ordering of
191     /// the variable objects!!! (it is up to the user to check this!) btw: most often,
192     /// this is called after FromVariablesToVector() to do a kind of 'undo', for example.
193     /// \return  the number of scalar variables (i.e. the rows of the column vector).
194     virtual int FromVectorToVariables(const ChVectorDynamic<>& mvector  ///< system-level vector 'q'
195     );
196 
197     /// Using this function, one may get a vector with all the constraint reactions 'l_i'
198     /// ordered into a column vector. The column vector must be passed as a ChMatrix<>
199     /// object, which will be automatically reset and resized to the proper length if necessary
200     /// (but uf you are sure that the vector has already the proper size, you can optimize
201     /// the performance a bit by setting resize_vector as false).
202     /// Optionally, you can pass an 'enabled' vector of bools, that must have the same
203     /// length of the l_i reactions vector; constraints with enabled=false are not handled.
204     /// \return  the number of scalar constr.multipliers (i.e. the rows of the column vector).
205     virtual int FromConstraintsToVector(ChVectorDynamic<>& mvector,  ///< system-level vector 'l_i'
206                                         bool resize_vector = true    ///< if true, resize vector as necessary
207     );
208 
209     /// Using this function, one may go in the opposite direction of the FromConstraintsToVector()
210     /// function, i.e. one gives a vector with all the constr.reactions 'l_i' ordered into a column vector, and
211     /// the constraint objects are updated according to these values.
212     /// Optionally, you can pass an 'enabled' vector of bools, that must have the same
213     /// length of the l_i reactions vector; constraints with enabled=false are not handled.
214     /// NOTE!!! differently from  FromConstraintsToVector(), which always works, this
215     /// function will fail if mvector does not match the amount and ordering of
216     /// the variable objects!!! (it is up to the user to check this!) btw: most often,
217     /// this is called after FromConstraintsToVector() to do a kind of 'undo', for example.
218     /// \return  the number of scalar constraint multipliers (i.e. the rows of the column vector).
219     virtual int FromVectorToConstraints(const ChVectorDynamic<>& mvector  ///< system-level vector 'l_i'
220     );
221 
222     /// Using this function, one may get a vector with all the unknowns x={q,l} i.e. q variables & l_i constr.
223     /// ordered into a column vector. The column vector must be passed as a ChMatrix<>
224     /// object, which will be automatically reset and resized to the proper length if necessary
225     /// (but if you are sure that the vector has already the proper size, you can optimize
226     /// the performance a bit by setting resize_vector as false).
227     /// \return  the number of scalar unknowns
228     virtual int FromUnknownsToVector(ChVectorDynamic<>& mvector,  ///< system-level vector x={q,l}
229                                      bool resize_vector = true    ///< if true, resize vector as necessary
230     );
231 
232     /// Using this function, one may go in the opposite direction of the FromUnknownsToVector()
233     /// function, i.e. one gives a vector with all the unknowns x={q,l} ordered into a column vector, and
234     /// the variables q and constr.multipliers l objects are updated according to these values.
235     /// NOTE!!! differently from  FromUnknownsToVector(), which always works, this
236     /// function will fail if mvector does not match the amount and ordering of
237     /// the variable and constraint objects!!! (it is up to the user to check this!)
238     virtual int FromVectorToUnknowns(const ChVectorDynamic<>& mvector  ///< system-level vector x={q,l}
239     );
240 
241     // MATHEMATICAL OPERATIONS ON DATA
242 
243     /// Performs the product of N, the Shur complement of the KKT matrix, by an 'l' vector
244     /// <pre>
245     ///    result = [N]*l = [ [Cq][M^(-1)][Cq'] - [E] ] * l
246     /// </pre>
247     /// where [Cq] are the jacobians, [M] is the mass matrix, [E] is the matrix
248     /// of the optional cfm 'constraint force mixing' terms for compliant constraints.
249     /// The N matrix is not built explicitly, to exploit sparsity, it is described by the
250     /// inserted constraints and inserted variables.
251     /// Optionally, you can pass an 'enabled' vector of bools, that must have the same
252     /// length of the l_i reactions vector; constraints with enabled=false are not handled.
253     /// NOTE! the 'q' data in the ChVariables of the system descriptor is changed by this
254     /// operation, so it may happen that you need to backup them via FromVariablesToVector()
255     /// NOTE! currently this function does NOT support the cases that use also ChKblock
256     /// objects, because it would need to invert the global M+K, that is not diagonal,
257     /// for doing = [N]*l = [ [Cq][(M+K)^(-1)][Cq'] - [E] ] * l
258     virtual void ShurComplementProduct(
259         ChVectorDynamic<>& result,            ///< result of  N * l_i
260         const ChVectorDynamic<>& lvector,     ///< vector to be multiplied
261         std::vector<bool>* enabled = nullptr  ///< optional: vector of "enabled" flags, one per scalar constraint.
262     );
263 
264     /// Performs the product of the entire system matrix (KKT matrix), by a vector x ={q,l}.
265     /// Note that the 'q' data in the ChVariables of the system descriptor is changed by this
266     /// operation, so thay may need to be backed up via FromVariablesToVector()
267     virtual void SystemProduct(ChVectorDynamic<>& result,  ///< result vector (multiplication of system matrix by x)
268                                const ChVectorDynamic<>& x  ///< vector to be multiplied
269     );
270 
271     /// Performs projection of constraint multipliers onto allowed set (in case
272     /// of bilateral constraints it does not affect multipliers, but for frictional
273     /// constraints, for example, it projects multipliers onto the friction cones)
274     /// Note! the 'l_i' data in the ChConstraints of the system descriptor are changed
275     /// by this operation (they get the value of 'multipliers' after the projection), so
276     /// it may happen that you need to backup them via FromConstraintToVector().
277     virtual void ConstraintsProject(
278         ChVectorDynamic<>& multipliers  ///< system-level vector of 'l_i' multipliers to be projected
279     );
280 
281     /// As ConstraintsProject(), but instead of passing the l vector, the entire
282     /// vector of unknowns x={q,-l} is passed.
283     /// Note! the 'l_i' data in the ChConstraints of the system descriptor are changed
284     /// by this operation (they get the value of 'multipliers' after the projection), so
285     /// it may happen that you need to backup them via FromConstraintToVector().
286     virtual void UnknownsProject(
287         ChVectorDynamic<>& mx  ///< system-level vector of unknowns x={q,-l} (only the l part is projected)
288     );
289 
290     /// The following (obsolete) function may be called after a solver's 'Solve()'
291     /// operation has been performed. This gives an estimate of 'how
292     /// good' the solver had been in finding the proper solution.
293     /// Resulting estimates are passed as references in member arguments.
294     virtual void ComputeFeasabilityViolation(
295         double& resulting_maxviolation,  ///< gets the max constraint violation (either bi- and unilateral.)
296         double& resulting_feasability    ///< gets the max feasability as max |l*c| , for unilateral only
297     );
298 
299     // LOGGING/OUTPUT/ETC.
300 
301     /// The following function may be used to create the Jacobian and the
302     /// mass matrix of the variational problem in matrix form, by assembling all
303     /// the jacobians of all the constraints/contacts, all the mass matrices, all vectors,
304     /// as they are _currently_ stored in the sparse data of all ChConstraint and ChVariables
305     /// contained in this ChSystemDescriptor.
306     ///
307     /// This can be useful for debugging, data dumping, and similar purposes (most solvers avoid
308     /// using these matrices, for performance), for example you will load these matrices in Matlab.
309     /// Optionally, tangential (u,v) contact jacobians may be skipped, or only bilaterals can be considered
310     /// The matrices and vectors are automatically resized if needed.
311     virtual void ConvertToMatrixForm(
312         ChSparseMatrix* Cq,            ///< fill this system jacobian matrix, if not null
313         ChSparseMatrix* H,             ///< fill this system H (mass+stiffness+damp) matrix, if not null
314         ChSparseMatrix* E,             ///< fill this system 'compliance' matrix , if not null
315         ChVectorDynamic<>* Fvector,    ///< fill this vector as the known term 'f', if not null
316         ChVectorDynamic<>* Bvector,    ///< fill this vector as the known term 'b', if not null
317         ChVectorDynamic<>* Frict,      ///< fill as a vector with friction coefficients (=-1 for tangent comp.; =-2 for
318                                        ///< bilaterals), if not null
319         bool only_bilaterals = false,  ///< skip unilateral constraints
320         bool skip_contacts_uv = false  ///< skip the tangential reaction constraints
321     );
322 
323     /// Create and return the assembled system matrix and RHS vector.
324     virtual void ConvertToMatrixForm(ChSparseMatrix* Z,      ///< [out] assembled system matrix
325                                      ChVectorDynamic<>* rhs  ///< [out] assembled RHS vector
326     );
327 
328     /// Saves to disk the LAST used matrices of the problem.
329     /// If assembled == true,
330     ///    dump_Z.dat   has the assembled optimization matrix (Matlab sparse format)
331     ///    dump_rhs.dat has the assembled RHS
332     /// Otherwise,
333     ///    dump_H.dat   has masses and/or stiffness (Matlab sparse format)
334     ///    dump_Cq.dat  has the jacobians (Matlab sparse format)
335     ///    dump_E.dat   has the constr.compliance (Matlab sparse format)
336     ///    dump_f.dat   has the applied loads
337     ///    dump_b.dat   has the constraint rhs
338     virtual void DumpLastMatrices(bool assembled = false, const char* path = "");
339 
340     /// Method to allow serialization of transient data to archives.
ArchiveOUT(ChArchiveOut & marchive)341     virtual void ArchiveOUT(ChArchiveOut& marchive) {
342         // version number
343         marchive.VersionWrite<ChSystemDescriptor>();
344         // serialize parent class
345         // serialize all member data:
346     }
347 
348     /// Method to allow de-serialization of transient data from archives.
ArchiveIN(ChArchiveIn & marchive)349     virtual void ArchiveIN(ChArchiveIn& marchive) {
350         // version number
351         /*int version =*/ marchive.VersionRead<ChSystemDescriptor>();
352         // deserialize parent class
353         // stream in all member data:
354     }
355 };
356 
357 CH_CLASS_VERSION(ChSystemDescriptor, 0)
358 
359 }  // end namespace chrono
360 
361 #endif
362