chrono::ChSystemDescriptor Class Reference

Description

Base class for collecting objects inherited from ChConstraint, ChVariables and optionally ChKRMBlock.

These objects can be used to define a sparse representation of the system. This collector is important because it contains all the required information that is sent to a solver (usually a VI/CCP solver, or as a subcase, a linear solver).
The problem is described by a variational inequality VI(Z*x-d,K):
The matrix \(Z\) that represents the problem has this form:

 | H -Cq'|*|q|- | f|= |0|
 | Cq -E | |l|  |-b|  |c|

with \(Y \ni \mathbb{l} \perp \mathbb{c} \in N_y\)
where \(N_y\) is the normal cone to \(Y\)
By flipping the sign of \(l_i\), the matrix \(Z\) can be symmetric (but in general non positive definite)

| H  Cq'|*| q|-| f|=|0|
| Cq  E | |-l| |-b| |c|
  • Linear Problem: \( \forall i \,Y_i = \mathbb{R}, N_{y_{i}} = 0\) (e.g. all bilateral)
  • Linear Complementarity Problem (LCP): \( 0\le c \perp l\ge0 \) (i.e. \(Y_i = \mathbb{R}^+\))
  • Cone Complementarity Problem (CCP): \(Y \ni \mathbb{l} \perp \mathbb{c} \in N_y\) ( \(Y_i\) are friction cones)

Notes

  1. most often you call BuildSystemMatrix() right after a dynamic simulation step, in order to get the system matrices updated to the last timestep;
  2. when using Anitescu default stepper, the 'f' vector contains forces*timestep = F*dt
  3. when using Anitescu default stepper, 'q' represents the 'delta speed',
  4. when using Anitescu default stepper, 'b' represents the dt/phi stabilization term.
  5. usually, H = M, the mass matrix, but in some cases, ex. when using implicit integrators, objects inherited from ChKRMBlock can be added too, hence H could be H=a*M+b*K+c*R (but not all solvers handle ChKRMBlock!)

All solvers require that the description of the system is passed by means of a ChSystemDescriptor object that holds a list of all the constraints, variables, masses, known terms (ex.forces) under the form of ChVariables, ChConstraints and ChKRMBlock.

In this default implementation, the ChSystemDescriptor simply holds a vector of pointers to ChVariables or to ChConstraints, but more advanced implementations (ex. for supporting parallel GPU solvers) could store constraints and variables structures with other, more efficient data schemes.

#include <ChSystemDescriptor.h>

Public Member Functions

std::vector< ChConstraint * > & GetConstraints ()
 Access the vector of constraints.
 
std::vector< ChVariables * > & GetVariables ()
 Access the vector of variables.
 
virtual void BeginInsertion ()
 Begin insertion of items.
 
virtual void InsertConstraint (ChConstraint *mc)
 Insert reference to a ChConstraint object.
 
virtual void InsertVariables (ChVariables *mv)
 Insert reference to a ChVariables object.
 
virtual void InsertKRMBlock (ChKRMBlock *mk)
 Insert reference to a ChKRMBlock object (a piece of matrix).
 
virtual void EndInsertion ()
 End insertion of items. More...
 
virtual unsigned int CountActiveVariables () const
 Count & returns the scalar variables in the system. More...
 
virtual unsigned int CountActiveConstraints () const
 Count & returns the scalar constraints in the system This excludes ChConstraint object that are set as inactive. More...
 
virtual void UpdateCountsAndOffsets ()
 Update counts of scalar variables and scalar constraints.
 
virtual void SetMassFactor (const double mc_a)
 Set the c_a coefficient (default=1) used for scaling the M masses of the m_variables. More...
 
virtual double GetMassFactor ()
 Get the c_a coefficient (default=1) used for scaling the M masses of the m_variables.
 
virtual unsigned int BuildFbVector (ChVectorDynamic<> &f, unsigned int start_row=0) const
 Gather all 'fb' known terms from all variables into a column vector. More...
 
virtual unsigned int BuildBiVector (ChVectorDynamic<> &b, unsigned int start_row=0) const
 Gather the constraint residuals 'bi' into a coluimn vector. More...
 
virtual unsigned int BuildDiVector (ChVectorDynamic<> &d) const
 Get the vector d = {f; -b} with all the 'fb' and 'bi' known terms, as in Z*y-d. More...
 
virtual unsigned int BuildDiagonalVector (ChVectorDynamic<> &diagonal_vect) const
 Get the D diagonal of the Z system matrix, as a single column vector. More...
 
virtual unsigned int FromVariablesToVector (ChVectorDynamic<> &vector, bool resize_vector=true) const
 Gather the 'q' tertms from all variables into a column vector. More...
 
virtual unsigned int FromVectorToVariables (const ChVectorDynamic<> &vector)
 Scatter the given vector to the 'q' terms for all variables. More...
 
virtual unsigned int FromConstraintsToVector (ChVectorDynamic<> &vector, bool resize_vector=true) const
 Gather all constraint reactions 'l' into a column vector. More...
 
virtual unsigned int FromVectorToConstraints (const ChVectorDynamic<> &vector)
 Scatter the given vector to the constraint reaction terms 'l' for all constraints. More...
 
virtual unsigned int FromUnknownsToVector (ChVectorDynamic<> &vector, bool resize_vector=true) const
 Gather all unknows x = {q,l} into a column vector. More...
 
virtual unsigned int FromVectorToUnknowns (const ChVectorDynamic<> &vector)
 Scatter the given vector to the variables 'q' and constraint multipliers 'l'. More...
 
bool HasKRMBlocks ()
 Return true if the system descriptor contains KRM blocks.
 
bool SupportsSchurComplement ()
 Return true if the system descriptor supports Schur complement-based solvers. More...
 
void SetMassInverse (ChMatrixConstRef M_inverse)
 Set the inverse mass matrix. More...
 
bool HasMassInverse () const
 Return true if an inverse mass matrix was provided.
 
void SchurComplementUpdateConstraints (bool average)
 Update constraints in the system. More...
 
void SchurComplementIncrementVariables (const ChVectorDynamic<> *Mif=nullptr)
 Update all variables in the system. More...
 
void SchurComplementIncrementVariables (const ChVectorDynamic<> &lvector)
 Update all variables in the system by M^(-1) * Cq' * lvector.
 
virtual void SchurComplementProduct (ChVectorDynamic<> &result, const ChVectorDynamic<> &lvector, ChVectorDynamic<> *idiag=nullptr)
 Performs the product of N, the Schur complement of the KKT matrix, by an 'l' vector. More...
 
void SchurComplementRHS (ChVectorDynamic<> &b_Schur, ChVectorDynamic<> *Mif=nullptr)
 Calculate the RHS of the Schur complement equation. More...
 
virtual void SystemProduct (ChVectorDynamic<> &result, const ChVectorDynamic<> &x)
 Performs the product of the entire system matrix (KKT matrix), by a vector x={q,l}. More...
 
void SystemProductUpper (ChVectorDynamic<> &result, const ChVectorDynamic<> &v, const ChVectorDynamic<> &l, bool negate_lambda)
 Compute upper part of system descriptor product, as in [Z]*y = d -> res = [H]*v + [CqT]*l. More...
 
void SystemProductLower (ChVectorDynamic<> &result, const ChVectorDynamic<> &v, const ChVectorDynamic<> &l, bool negate_lambda)
 Compute lower part of system descriptor product, as in [Z]*y = d -> res = [Cq]*v + [E]*l. More...
 
virtual void ConstraintsProject (ChVectorDynamic<> &multipliers)
 Performs projection of constraint multipliers onto allowed set (in case of bilateral constraints it does not affect multipliers, but for frictional constraints, for example, it projects multipliers onto the friction cones) Note! the 'l_i' data in the ChConstraints of the system descriptor are changed by this operation (they get the value of 'multipliers' after the projection), so it may happen that you need to backup them via FromConstraintToVector(). More...
 
virtual void UnknownsProject (ChVectorDynamic<> &mx)
 As ConstraintsProject(), but instead of passing the l vector, the entire vector of unknowns x={q,-l} is passed. More...
 
virtual void ComputeFeasabilityViolation (double &resulting_maxviolation, double &resulting_feasability)
 The following (obsolete) function may be called after a solver's 'Solve()' operation has been performed. More...
 
void PasteMassKRMMatrixInto (ChSparseMatrix &Z, unsigned int start_row=0, unsigned int start_col=0) const
 Paste the stiffness, damping or mass matrix of the system into a sparse matrix. More...
 
unsigned int PasteConstraintsJacobianMatrixInto (ChSparseMatrix &Z, unsigned int start_row=0, unsigned int start_col=0, bool only_bilateral=false) const
 Paste the constraints jacobian of the system into a sparse matrix at a given position. More...
 
unsigned int PasteConstraintsJacobianMatrixTransposedInto (ChSparseMatrix &Z, unsigned int start_row=0, unsigned int start_col=0, bool only_bilateral=false) const
 Paste the transposed constraints jacobian of the system into a sparse matrix at a given position. More...
 
void PasteComplianceMatrixInto (ChSparseMatrix &Z, unsigned int start_row=0, unsigned int start_col=0, bool only_bilateral=false) const
 Paste E, the negative compliance matrix of the system into a sparse matrix at a given position. More...
 
virtual void BuildSystemMatrix (ChSparseMatrix *Z, ChVectorDynamic<> *rhs) const
 Create and return the assembled system matrix and RHS vector at a given position. More...
 
virtual void WriteMatrixBlocks (const std::string &path, const std::string &prefix, bool one_indexed=true)
 Write the current system matrix blocks and right-hand side components. More...
 
virtual void WriteMatrix (const std::string &path, const std::string &prefix, bool one_indexed=true)
 Write the current assembled system matrix and right-hand side vector. More...
 
virtual void WriteMatrixSpmv (const std::string &path, const std::string &prefix, bool one_indexed=true)
 Write the current assembled system matrix and right-hand side vector. More...
 
virtual void ArchiveOut (ChArchiveOut &archive_out)
 Method to allow serialization of transient data to archives.
 
virtual void ArchiveIn (ChArchiveIn &archive_in)
 Method to allow de-serialization of transient data from archives.
 

Protected Attributes

std::vector< ChConstraint * > m_constraints
 list of all constraints in the current Chrono system
 
std::vector< ChVariables * > m_variables
 list of all variables in the current Chrono system
 
std::vector< ChKRMBlock * > m_KRMblocks
 list of all KRM blocks in the current Chrono system
 
double c_a
 coefficient form M mass matrices in m_variables
 

Member Function Documentation

◆ BuildBiVector()

unsigned int chrono::ChSystemDescriptor::BuildBiVector ( ChVectorDynamic<> &  b,
unsigned int  start_row = 0 
) const
virtual

Gather the constraint residuals 'bi' into a coluimn vector.

The column vector will be automatically reset and resized to the proper length if necessary.

Parameters
bsystem-level vector 'b'
start_rowoffset in global 'b' vector

◆ BuildDiagonalVector()

unsigned int chrono::ChSystemDescriptor::BuildDiagonalVector ( ChVectorDynamic<> &  diagonal_vect) const
virtual

Get the D diagonal of the Z system matrix, as a single column vector.

This includes all the diagonal masses of M, and all the diagonal E (-cfm) terms. The diagonal_vect must already have size equal to the number of unknowns, otherwise it will be resized as necessary.

◆ BuildDiVector()

unsigned int chrono::ChSystemDescriptor::BuildDiVector ( ChVectorDynamic<> &  d) const
virtual

Get the vector d = {f; -b} with all the 'fb' and 'bi' known terms, as in Z*y-d.

This vector is the concatenation of BuildFbVector and BuildBiVector. It will be automatically reset and resized to the proper length if necessary.

◆ BuildFbVector()

unsigned int chrono::ChSystemDescriptor::BuildFbVector ( ChVectorDynamic<> &  f,
unsigned int  start_row = 0 
) const
virtual

Gather all 'fb' known terms from all variables into a column vector.

The column vector will be automatically reset and resized to the proper length if necessary.

Parameters
fsystem-level vector 'f'
start_rowoffset in global 'f' vector

◆ BuildSystemMatrix()

void chrono::ChSystemDescriptor::BuildSystemMatrix ( ChSparseMatrix Z,
ChVectorDynamic<> *  rhs 
) const
virtual

Create and return the assembled system matrix and RHS vector at a given position.

Parameters
[out]Z[out] assembled system matrix
[out]rhs[out] assembled RHS vector

◆ ComputeFeasabilityViolation()

void chrono::ChSystemDescriptor::ComputeFeasabilityViolation ( double &  resulting_maxviolation,
double &  resulting_feasability 
)
virtual

The following (obsolete) function may be called after a solver's 'Solve()' operation has been performed.

This gives an estimate of 'how good' the solver had been in finding the proper solution. Resulting estimates are passed as references in member arguments.

Parameters
resulting_maxviolationgets the max constraint violation (either bi- and unilateral.)
resulting_feasabilitygets the max feasability as max |l*c| , for unilateral only

◆ ConstraintsProject()

void chrono::ChSystemDescriptor::ConstraintsProject ( ChVectorDynamic<> &  multipliers)
virtual

Performs projection of constraint multipliers onto allowed set (in case of bilateral constraints it does not affect multipliers, but for frictional constraints, for example, it projects multipliers onto the friction cones) Note! the 'l_i' data in the ChConstraints of the system descriptor are changed by this operation (they get the value of 'multipliers' after the projection), so it may happen that you need to backup them via FromConstraintToVector().

Parameters
multiplierssystem-level vector of 'l_i' multipliers to be projected

◆ CountActiveConstraints()

unsigned int chrono::ChSystemDescriptor::CountActiveConstraints ( ) const
virtual

Count & returns the scalar constraints in the system This excludes ChConstraint object that are set as inactive.

Note that this also updates the offsets of all constraints in 'l' global vector (see GetOffset() in ChConstraint).

◆ CountActiveVariables()

unsigned int chrono::ChSystemDescriptor::CountActiveVariables ( ) const
virtual

Count & returns the scalar variables in the system.

This excludes ChVariable object that are set as inactive. Notes:

  • the number of scalar variables is not necessarily the number of inserted ChVariable objects, some could be inactive.
  • also updates the offsets of all variables in 'q' global vector (see GetOffset() in ChVariables).

◆ EndInsertion()

virtual void chrono::ChSystemDescriptor::EndInsertion ( )
inlinevirtual

End insertion of items.

A derived class should always call UpdateCountsAndOffsets.

◆ FromConstraintsToVector()

unsigned int chrono::ChSystemDescriptor::FromConstraintsToVector ( ChVectorDynamic<> &  vector,
bool  resize_vector = true 
) const
virtual

Gather all constraint reactions 'l' into a column vector.

The column vectorwill be automatically reset and resized to the proper length if requested.

Returns
the number of scalar constr.multipliers (i.e. the rows of the column vector).
Parameters
vectorsystem-level vector 'l_i'
resize_vectorif true, resize vector as necessary

◆ FromUnknownsToVector()

unsigned int chrono::ChSystemDescriptor::FromUnknownsToVector ( ChVectorDynamic<> &  vector,
bool  resize_vector = true 
) const
virtual

Gather all unknows x = {q,l} into a column vector.

The column vector will be automatically reset and resized to the proper length if requested.

Returns
the number of scalar unknowns
Parameters
vectorsystem-level vector x={q,l}
resize_vectorif true, resize vector as necessary

◆ FromVariablesToVector()

unsigned int chrono::ChSystemDescriptor::FromVariablesToVector ( ChVectorDynamic<> &  vector,
bool  resize_vector = true 
) const
virtual

Gather the 'q' tertms from all variables into a column vector.

The column vector will be automatically reset and resized to the proper length if requested.

Returns
the number of scalar variables (i.e. the rows of the column vector).
Parameters
vectorsystem-level vector 'q'
resize_vectorif true, resize vector as necessary

◆ FromVectorToConstraints()

unsigned int chrono::ChSystemDescriptor::FromVectorToConstraints ( const ChVectorDynamic<> &  vector)
virtual

Scatter the given vector to the constraint reaction terms 'l' for all constraints.

Note that no check on the size and ordering of the provided vector is performed.

Returns
the number of scalar constraint multipliers (i.e. the rows of the column vector).

◆ FromVectorToUnknowns()

unsigned int chrono::ChSystemDescriptor::FromVectorToUnknowns ( const ChVectorDynamic<> &  vector)
virtual

Scatter the given vector to the variables 'q' and constraint multipliers 'l'.

Note that no check on the size and ordering of the provided vector is performed.

Returns
the number of scalar unknowns

◆ FromVectorToVariables()

unsigned int chrono::ChSystemDescriptor::FromVectorToVariables ( const ChVectorDynamic<> &  vector)
virtual

Scatter the given vector to the 'q' terms for all variables.

Note that no check on the size and ordering of the provided vector is performed.

Returns
the number of scalar variables (i.e. the rows of the column vector).

◆ PasteComplianceMatrixInto()

void chrono::ChSystemDescriptor::PasteComplianceMatrixInto ( ChSparseMatrix Z,
unsigned int  start_row = 0,
unsigned int  start_col = 0,
bool  only_bilateral = false 
) const

Paste E, the negative compliance matrix of the system into a sparse matrix at a given position.

Before calling this function the user needs to:

  • resize Z (and potentially call SetZeroValues if the case)
  • call LoadKRMMatrices with the desired factors
  • call SetMassFactor() with the appropriate value

◆ PasteConstraintsJacobianMatrixInto()

unsigned int chrono::ChSystemDescriptor::PasteConstraintsJacobianMatrixInto ( ChSparseMatrix Z,
unsigned int  start_row = 0,
unsigned int  start_col = 0,
bool  only_bilateral = false 
) const

Paste the constraints jacobian of the system into a sparse matrix at a given position.

Before calling this function the user needs to:

  • resize Z (and potentially call SetZeroValues if the case)
  • call LoadConstraintJacobians Returns the number of pasted constraints.

◆ PasteConstraintsJacobianMatrixTransposedInto()

unsigned int chrono::ChSystemDescriptor::PasteConstraintsJacobianMatrixTransposedInto ( ChSparseMatrix Z,
unsigned int  start_row = 0,
unsigned int  start_col = 0,
bool  only_bilateral = false 
) const

Paste the transposed constraints jacobian of the system into a sparse matrix at a given position.

Before calling this function the user needs to:

  • resize Z (and potentially call SetZeroValues if the case)
  • call LoadConstraintJacobians Returns the number of pasted constraints.

◆ PasteMassKRMMatrixInto()

void chrono::ChSystemDescriptor::PasteMassKRMMatrixInto ( ChSparseMatrix Z,
unsigned int  start_row = 0,
unsigned int  start_col = 0 
) const

Paste the stiffness, damping or mass matrix of the system into a sparse matrix.

Before calling this function the user needs to:

  • resize Z (and potentially call SetZeroValues if the case)
  • call LoadKRMMatrices with the desired factors
  • call SetMassFactor() with the appropriate value

◆ SchurComplementIncrementVariables()

void chrono::ChSystemDescriptor::SchurComplementIncrementVariables ( const ChVectorDynamic<> *  Mif = nullptr)

Update all variables in the system.

The 'q' data for the system ChVariables will be

  incremented by: M^(-1) * Cq' * l,         if 'Mif' is NULL, or
  set to:         Mif + M^(-1) * Cq' * l,   if 'Mif' is non-NULL,

where [l] is the vector of Lagrange multipliers.

◆ SchurComplementProduct()

void chrono::ChSystemDescriptor::SchurComplementProduct ( ChVectorDynamic<> &  result,
const ChVectorDynamic<> &  lvector,
ChVectorDynamic<> *  idiag = nullptr 
)
virtual

Performs the product of N, the Schur complement of the KKT matrix, by an 'l' vector.

   result = N * l = [ CqM^(-1)Cq' - E ] * l

where [Cq] is the constraint Jacobian, [M] is the mass matrix, [E] is the matrix of the optional 'constraint force mixing' terms for compliant constraints. If an inverse mass matrix is not provided (default), the N matrix is never built explicitly; instead, it is described by the inserted constraints and inserted variables. If non-NULL, the vector idiag will contain the inverse diagonal of the Schur complement matrix N (automatically resized). NOTES:

  • the 'q' data in the ChVariables of the system descriptor is changed by this operation, so it may need to be cached them via FromVariablesToVector().
  • unless the inverse of the matrix (M+K) is provided, this function does NOT support systems that include ChKRMBlock objects.
Parameters
resultresult of N * l_i
lvectorvector to be multiplied
idiag(optional) inverse diagonal

◆ SchurComplementRHS()

void chrono::ChSystemDescriptor::SchurComplementRHS ( ChVectorDynamic<> &  b_Schur,
ChVectorDynamic<> *  Mif = nullptr 
)

Calculate the RHS of the Schur complement equation.

   result = Cq'*(M^-1) * f + b

where [Cq] is the constraint Jacobian, [M] is the mass matrix, and [b] is the RHS of the KKT equation. If non-NULL, the vector Mif will contain the intermediate values (M^-1)*f (automatically resized).

Parameters
b_Schurtransformed RHS
Mif(optional) intermediate quantity Minv*f

◆ SchurComplementUpdateConstraints()

void chrono::ChSystemDescriptor::SchurComplementUpdateConstraints ( bool  average)

Update constraints in the system.

This function calls ChConstraint::UpdateAuxiliary to calculate entries in the Schur complement matrix corresponding to each constraint and, optionally, averages these entries for friction constraints (NSC).

◆ SetMassFactor()

virtual void chrono::ChSystemDescriptor::SetMassFactor ( const double  mc_a)
inlinevirtual

Set the c_a coefficient (default=1) used for scaling the M masses of the m_variables.

Used when performing SchurComplementProduct(), SystemProduct(), BuildSystemMatrix().

◆ SetMassInverse()

void chrono::ChSystemDescriptor::SetMassInverse ( ChMatrixConstRef  M_inverse)

Set the inverse mass matrix.

If provided, this matrix is used in calculating the Schur complement (for both SchurComplementProduct and SchurComplementRHS); this allows using solver based on the Schur complement also for problems that have a non-block diagonal generalized mass matrix (e.g., when using hydrodynamic loads which include so-called "added mass" terms. NOTE: use this approach only for moderatley large problems and only if the inverse calculation is not expensive (e.g., for a constant mass matrix for which the inverse van be pre-computed).

◆ SupportsSchurComplement()

bool chrono::ChSystemDescriptor::SupportsSchurComplement ( )

Return true if the system descriptor supports Schur complement-based solvers.

That means that:

  • the system does not include KRM blocks, or
  • the system does not include KR blocks and an inverse mass matrix is provided.

◆ SystemProduct()

void chrono::ChSystemDescriptor::SystemProduct ( ChVectorDynamic<> &  result,
const ChVectorDynamic<> &  x 
)
virtual

Performs the product of the entire system matrix (KKT matrix), by a vector x={q,l}.

Note that the 'q' data in the ChVariables of the system descriptor is changed by this operation, so that may need to be backed up via FromVariablesToVector().

Parameters
resultresult vector (multiplication of system matrix by x)
xvector to be multiplied

◆ SystemProductLower()

void chrono::ChSystemDescriptor::SystemProductLower ( ChVectorDynamic<> &  result,
const ChVectorDynamic<> &  v,
const ChVectorDynamic<> &  l,
bool  negate_lambda 
)

Compute lower part of system descriptor product, as in [Z]*y = d -> res = [Cq]*v + [E]*l.

Note:

  • 'result' is automatically resized
  • if negate_lambda = true, automatically flip sign to provided lambda.
Parameters
resultresult vector
vprimal variable (e.g. generalized velocity)
ldual variable (e.g. lagrange multipliers)
negate_lambdaflip sign to dual variable

◆ SystemProductUpper()

void chrono::ChSystemDescriptor::SystemProductUpper ( ChVectorDynamic<> &  result,
const ChVectorDynamic<> &  v,
const ChVectorDynamic<> &  l,
bool  negate_lambda 
)

Compute upper part of system descriptor product, as in [Z]*y = d -> res = [H]*v + [CqT]*l.

Note:

  • 'result' is automatically resized
  • if negate_lambda = true, automatically flip sign to provided lambda.
Parameters
resultresult vector
vprimal variable (e.g. generalized velocity)
ldual variable (e.g. lagrange multipliers)
negate_lambdaflip sign to dual variable

◆ UnknownsProject()

void chrono::ChSystemDescriptor::UnknownsProject ( ChVectorDynamic<> &  mx)
virtual

As ConstraintsProject(), but instead of passing the l vector, the entire vector of unknowns x={q,-l} is passed.

Note! the 'l_i' data in the ChConstraints of the system descriptor are changed by this operation (they get the value of 'multipliers' after the projection), so it may happen that you need to backup them via FromConstraintToVector().

Parameters
mxsystem-level vector of unknowns x={q,-l} (only the l part is projected)

◆ WriteMatrix()

void chrono::ChSystemDescriptor::WriteMatrix ( const std::string &  path,
const std::string &  prefix,
bool  one_indexed = true 
)
virtual

Write the current assembled system matrix and right-hand side vector.

The system matrix is formed by calling BuildSystemMatrix() as used with direct linear solvers. The following files are written in the directory specified by [path]:

  • [prefix]_Z.dat the assembled optimization matrix (COO sparse format)
  • [prefix]_rhs.dat the assmbled RHS By default, uses 1-based indices (as in Matlab).

◆ WriteMatrixBlocks()

void chrono::ChSystemDescriptor::WriteMatrixBlocks ( const std::string &  path,
const std::string &  prefix,
bool  one_indexed = true 
)
virtual

Write the current system matrix blocks and right-hand side components.

The system matrix is formed by calling BuildSystemMatrix() as used with direct linear solvers. The following files are written in the directory specified by [path]:

  • [prefix]_H.dat masses and/or stiffness (Matlab sparse format)
  • [prefix]_Cq.dat Jacobians (Matlab sparse format)
  • [prefix]_E.dat constraint negative compliance (Matlab sparse format)
  • [prefix]_f.dat applied loads
  • [prefix]_b.dat constraint rhs By default, uses 1-based indices (as in Matlab).

◆ WriteMatrixSpmv()

void chrono::ChSystemDescriptor::WriteMatrixSpmv ( const std::string &  path,
const std::string &  prefix,
bool  one_indexed = true 
)
virtual

Write the current assembled system matrix and right-hand side vector.

The system matrix is formed by multiple calls to SystemProduct() as used with iterative linear solvers. The following files are written in the directory specified by [path]:

  • [prefix]_Z.dat the assembled optimization matrix (Matlab sparse format)
  • [prefix]_rhs.dat the assmbled RHS By default, uses 1-based indices (as in Matlab).

The documentation for this class was generated from the following files:
  • /builds/uwsbel/chrono/src/chrono/solver/ChSystemDescriptor.h
  • /builds/uwsbel/chrono/src/chrono/solver/ChSystemDescriptor.cpp