Skip to content
Merged
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,6 @@ class SOFA_COMPONENT_COLLISION_DETECTION_ALGORITHM_API DirectSAPNarrowPhase : pu
*/
void updateBoxes();

SOFA_ATTRIBUTE_DISABLED__DRAWNARROWPHASE()
sofa::core::objectmodel::lifecycle::RemovedData d_draw{this, "v23.12", "v24.06", "draw", "Use display flag 'showDetectionOutputs' instead"}; ///< enable/disable display of results

Data<bool> d_showOnlyInvestigatedBoxes; ///< Show only boxes which will be sent to narrow phase
Data<int> d_nbPairs; ///< number of pairs of elements sent to narrow phase

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,6 @@ class SOFA_COMPONENT_COLLISION_DETECTION_ALGORITHM_API RayTraceNarrowPhase : pub
public:
SOFA_CLASS(RayTraceNarrowPhase, core::collision::NarrowPhaseDetection);

private:
SOFA_ATTRIBUTE_DISABLED__DRAWNARROWPHASE()
sofa::core::objectmodel::lifecycle::RemovedData bDraw{this, "v23.12", "v24.06", "draw", "Use display flag 'showDetectionOutputs' instead"}; ///< enable/disable display of results

protected:
RayTraceNarrowPhase() = default;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,23 +31,6 @@
# define SOFA_COMPONENT_COLLISION_DETECTION_ALGORITHM_API SOFA_IMPORT_DYNAMIC_LIBRARY
#endif

#ifdef SOFA_BUILD_SOFA_COMPONENT_COLLISION_DETECTION_ALGORITHM
#define SOFA_ATTRIBUTE_DISABLED__RENAME_COLLISIONPIPELINE()
#else
#define SOFA_ATTRIBUTE_DISABLED__RENAME_COLLISIONPIPELINE() \
SOFA_ATTRIBUTE_DISABLED( \
"v23.06", "v23.12", \
"DefaultPipeline renamed as CollisionPipeline in #3590: sofa/component/collision/detection/algorithm/CollisionPipeline.h")
#endif

#ifdef SOFA_BUILD_SOFA_COMPONENT_COLLISION_DETECTION
# define SOFA_ATTRIBUTE_DISABLED__DRAWNARROWPHASE()
#else
# define SOFA_ATTRIBUTE_DISABLED__DRAWNARROWPHASE() \
SOFA_ATTRIBUTE_DISABLED( \
"v23.12", "v24.06", "This data is not used anymore: the drawing is now controlled by a draw flag")
#endif

#ifdef SOFA_BUILD_SOFA_COMPONENT_COLLISION_DETECTION_ALGORITHM
#define SOFA_ATTRIBUTE_DEPRECATED__RENAME_DATA_IN_COLLISION_DETECTION_ALGORITHM()
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,28 +67,6 @@ public :
if (arg)
obj->parse(arg);

//SOFA_ATTRIBUTE_DISABLED("v21.12 (PR#2522)", "v24.06","This attribute was only added to build a compatibility layer on the response name.")
{
static const std::map<std::string,std::string> renamingResponseMethod = {
{"ray", "RayContact"},
{"default", "PenalityContactForceField"},
{"FrictionContact", "FrictionContactConstraint"},
{"registration", "RegistrationContactForceField"},
{"stick", "StickContactForceField"},
};

const std::string responseDesired = arg->getAttribute("response","");
const auto it = renamingResponseMethod.find(responseDesired);

if(it != renamingResponseMethod.end())
{
msg_error("CollisionResponse")
<< "Option \"" << it->first << "\" "
<< "for data \"response\" has been renamed since v21.12 (PR#2522). "
<< "Use \"" << it->second << "\" instead.";
}
}

return obj;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,9 +53,6 @@ class BarycentricContactMapper : public BaseContactMapper<TDataTypes>
typename MMapping::SPtr mapping;
typename MMapper::SPtr mapper;

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Size, sofa::Size);

BarycentricContactMapper()
: model(nullptr), mapping(nullptr), mapper(nullptr)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ template<class DataTypes>
class ContactMapper<collision::geometry::TetrahedronCollisionModel, DataTypes> : public BarycentricContactMapper<collision::geometry::TetrahedronCollisionModel, DataTypes>
{
public:
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);
typedef typename DataTypes::Real Real;
typedef typename DataTypes::Coord Coord;
sofa::Index addPoint(const Coord& P, sofa::Index index, Real&)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,6 @@ class SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER_API GenericConstraintSolver :
sofa::type::fixed_array<GenericConstraintProblem, CP_BUFFER_SIZE> m_cpBuffer;
sofa::type::fixed_array<bool, CP_BUFFER_SIZE> m_cpIsLocked;
GenericConstraintProblem *current_cp, *last_cp;
SOFA_ATTRIBUTE_DISABLED__GENERICCONSTRAINTSOLVER_CONSTRAINTCORRECTIONS() DeprecatedAndRemoved constraintCorrections; //use ConstraintSolverImpl::l_constraintCorrections instead

sofa::core::MultiVecDerivId m_lambdaId;
sofa::core::MultiVecDerivId m_dxId;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,6 @@ class SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER_API LCPConstraintSolver : publ
void keepContactForcesValue();

unsigned int _numConstraints;
SOFA_ATTRIBUTE_DEPRECATED__LCPCONSTRAINTSOLVERMUMEMBER() DeprecatedAndRemoved _mu;

/// Multigrid hierarchy is resized and cleared
void buildHierarchy();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,23 +38,6 @@ namespace sofa::component::constraint::lagrangian::solver
} // namespace sofa::component::constraint::lagrangian::solver


// deprecate _mu as member
#ifdef SOFA_BUILD_SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER
#define SOFA_ATTRIBUTE_DEPRECATED__LCPCONSTRAINTSOLVERMUMEMBER()
#else
#define SOFA_ATTRIBUTE_DEPRECATED__LCPCONSTRAINTSOLVERMUMEMBER() \
SOFA_ATTRIBUTE_DISABLED( \
"v23.12", "v24.06", "_mu is not a member anymore. Use the Data \"mu\" to get the friction value.")
#endif // SOFA_BUILD_SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER

#ifdef SOFA_BUILD_SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER
#define SOFA_ATTRIBUTE_DISABLED__GENERICCONSTRAINTSOLVER_CONSTRAINTCORRECTIONS()
#else
#define SOFA_ATTRIBUTE_DISABLED__GENERICCONSTRAINTSOLVER_CONSTRAINTCORRECTIONS() \
SOFA_ATTRIBUTE_DISABLED( \
"v23.12", "v23.12", "Use ConstraintSolverImpl::l_constraintCorrections instead")
#endif // SOFA_BUILD_SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER

#ifdef SOFA_BUILD_SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER
#define SOFA_ATTRIBUTE_DEPRECATED__RENAME_DATA_IN_CONSTRAINT_LAGRANGIAN_SOLVER()
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@ class DirectionProjectiveConstraint : public core::behavior::ProjectiveConstrain
typedef Data<VecDeriv> DataVecDeriv;
typedef Data<MatrixDeriv> DataMatrixDeriv;
typedef type::vector<Index> Indices;
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Vector3, sofa::type::Vec3);
typedef sofa::core::topology::TopologySubsetIndices IndexSubsetData;
typedef linearalgebra::EigenBaseSparseMatrix<SReal> BaseSparseMatrix;
typedef linearalgebra::EigenSparseMatrix<DataTypes,DataTypes> SparseMatrix;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,6 @@ class FixedProjectiveConstraint : public core::behavior::ProjectiveConstraintSet
typedef sofa::core::topology::TopologySubsetIndices SetIndex;
typedef sofa::core::topology::Point Point;

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Vec3, sofa::type::Vec3);
protected:
FixedProjectiveConstraint();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@ class LineProjectiveConstraint : public core::behavior::ProjectiveConstraintSet<
typedef Data<VecCoord> DataVecCoord;
typedef Data<VecDeriv> DataVecDeriv;
typedef Data<MatrixDeriv> DataMatrixDeriv;
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Vector3, sofa::type::Vec3);
typedef type::vector<Index> Indices;
typedef sofa::core::topology::TopologySubsetIndices IndexSubsetData;
typedef linearalgebra::EigenBaseSparseMatrix<SReal> BaseSparseMatrix;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,6 @@ class PlaneProjectiveConstraint : public core::behavior::ProjectiveConstraintSet
typedef typename SparseMatrix::Block Block; ///< projection matrix of a particle displacement to the plane
enum {bsize=SparseMatrix::Nin}; ///< size of a block

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Vector3, sofa::type::Vec3);

protected:
PlaneProjectiveConstraint();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,6 @@ class PointProjectiveConstraint : public core::behavior::ProjectiveConstraintSet
typedef type::vector<Index> SetIndexArray;
typedef sofa::core::topology::TopologySubsetIndices SetIndex;

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Vector3, sofa::type::Vec3);

protected:
PointProjectiveConstraint();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,6 @@ class GenerateRigidMass : public core::DataEngine
void doUpdate() override;

protected:
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Vector3, sofa::type::Vec3);
typedef type::fixed_array <unsigned int,3> MTriangle;
typedef type::fixed_array <unsigned int,4> MQuad;
typedef type::vector<unsigned int> MPolygon;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ class MeshBarycentricMapperEngine : public core::DataEngine
typedef typename DataTypes::Real Real;
typedef type::Vec<3,Real> Vec3;
typedef type::Mat<3,3,Real> Mat3x3;
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);
typedef typename sofa::type::vector<sofa::Index> VecIndices;

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,8 @@ class ComplementaryROI : public core::DataEngine
SOFA_CLASS(SOFA_TEMPLATE(ComplementaryROI, DataTypes), core::DataEngine);

typedef typename DataTypes::VecCoord VecCoord;

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);
typedef core::topology::BaseMeshTopology::SetIndex SetIndex;


ComplementaryROI();
~ComplementaryROI() override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@ class IndicesFromValues : public core::DataEngine
typedef T Value;
typedef sofa::type::vector<T> VecValue;

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);
typedef sofa::type::vector<sofa::Index> VecIndex;

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,6 @@ class SOFA_COMPONENT_ENGINE_SELECT_API MergeROIs : public sofa::core::DataEngine
public:
SOFA_CLASS(MergeROIs, DataEngine);

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Inherited, Inherit1);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);

//Input
Data<unsigned int> d_nbROIs; ///< size of indices/value vector
core::objectmodel::vectorData<type::vector<sofa::Index> > f_indices;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ class MeshBoundaryROI : public core::DataEngine
{
public:
SOFA_CLASS(MeshBoundaryROI, DataEngine);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Inherited, Inherit1);

typedef core::topology::BaseMeshTopology::Triangle Triangle;
typedef core::topology::BaseMeshTopology::SeqTriangles SeqTriangles;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,6 @@ class SelectConnectedLabelsROI : public sofa::core::DataEngine

typedef _T T;

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Inherited, Inherit1);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);

//Input
Data<unsigned int> d_nbLabels; ///< number of label lists
typedef type::vector<type::SVector<T> > VecVLabels;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,6 @@ class SelectLabelROI : public sofa::core::DataEngine
SOFA_CLASS(SOFA_TEMPLATE(SelectLabelROI,_T), DataEngine);

typedef _T T;
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Inherited, Inherit1);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);

//Input
Data<type::vector<type::SVector<T> > > d_labels; ///< lists of labels associated to each point/cell
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,6 @@ class ValuesFromIndices : public core::DataEngine
SOFA_CLASS(SOFA_TEMPLATE(ValuesFromIndices,T),core::DataEngine);
typedef T Value;
typedef sofa::type::vector<T> VecValue;

SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);
typedef sofa::type::vector<sofa::Index> VecIndex;

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ class MapIndices : public core::DataEngine
SOFA_CLASS(SOFA_TEMPLATE(MapIndices,T),core::DataEngine);
typedef T Value;
typedef sofa::type::vector<T> VecValue;
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);
typedef sofa::type::vector<sofa::Index> VecIndex;
typedef std::map<sofa::Index, sofa::Index> MapIndex;
protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,6 @@ class ROIValueMapper : public sofa::core::DataEngine
typedef core::DataEngine Inherited;

SOFA_CLASS(ROIValueMapper,Inherited);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Real, SReal);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Index, sofa::Index);

//Input
Data<unsigned int> nbROIs; ///< size of indices/value vector
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,6 @@ class BTDLinearSolver : public sofa::component::linearsolver::MatrixLinearSolver
Data<bool> d_subpartSolve; ///< Allows for the computation of a subpart of the system
Data<bool> d_verification; ///< verification of the subpartSolve

SOFA_ATTRIBUTE_DISABLED__BTDLINEARSOLVER_DATABLOCKSIZE("d_blockSize has been deleted, as it was never actually used.")
DeprecatedAndRemoved d_blockSize;

typedef typename Vector::SubVectorType SubVector;
typedef typename Matrix::SubMatrixType SubMatrix;
typedef typename Vector::Real Real;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,6 @@ class CholeskySolver : public sofa::component::linearsolver::MatrixLinearSolver<
typedef typename Vector::Real Real;
typedef sofa::component::linearsolver::MatrixLinearSolver<TMatrix,TVector> Inherit;

SOFA_ATTRIBUTE_DISABLED__SOLVER_DIRECT_VERBOSEDATA()
sofa::core::objectmodel::lifecycle::RemovedData f_verbose{this, "v23.12", "v24.06", "verbose", "This Data is no longer used"};

CholeskySolver();

/// Compute x such as Mx=b. M is not used, it must have been factored before using method invert(Matrix& M)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,9 +93,6 @@ class PrecomputedLinearSolver : public sofa::component::linearsolver::MatrixLine
Data<bool> d_use_file; ///< Dump system matrix in a file
Data<double> init_Tolerance;

SOFA_ATTRIBUTE_DISABLED__SOLVER_DIRECT_VERBOSEDATA()
sofa::core::objectmodel::lifecycle::RemovedData f_verbose{this, "v23.12", "v24.06", "verbose", "This Data is no longer used"};

PrecomputedLinearSolver();
void solve (TMatrix& M, TVector& x, TVector& b) override;
void invert(TMatrix& M) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,6 @@ SOFA_ATTRIBUTE_DEPRECATED__SPARSECOMMON()
SOFA_COMPONENT_LINEARSOLVER_DIRECT_API
void csrToAdj(int n, int * M_colptr, int * M_rowind, type::vector<int>& adj, type::vector<int>& xadj, type::vector<int>& t_adj, type::vector<int>& t_xadj, type::vector<int>& tran_countvec );

// compute the fill reducing permutation via METIS
SOFA_ATTRIBUTE_DISABLED("v24.06", "v24.06", "This function depends on Metis which has been removed as a dependency.")
void fillReducingPermutation(int nbColumns, int *columns, int* rowIndices,
int * perm,int * invperm) = delete;

// compare the shape of two matrix given in CSR format, return false if the matrices have the same shape and return true if their shapes are different
inline bool compareMatrixShape(int s_M, int * M_colptr,int * M_rowind, int s_P, int * P_colptr,int * P_rowind) {
if (s_M != s_P) return true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,21 +37,6 @@ namespace sofa::component::linearsolver::direct
constexpr const char* MODULE_VERSION = "@PROJECT_VERSION@";
} // namespace sofa::component::linearsolver::direct

#ifdef SOFA_BUILD_SOFA_COMPONENT_LINEARSOLVER_DIRECT
#define SOFA_ATTRIBUTE_DISABLED__BTDLINEARSOLVER_DATABLOCKSIZE(msg)
#else
#define SOFA_ATTRIBUTE_DISABLED__BTDLINEARSOLVER_DATABLOCKSIZE(msg) \
SOFA_ATTRIBUTE_DISABLED( \
"v23.06", "v23.12", msg)
#endif // SOFA_BUILD_SOFA_COMPONENT_LINEARSOLVER_DIRECT

#ifdef SOFA_BUILD_SOFA_COMPONENT_LINEARSOLVER_DIRECT
#define SOFA_ATTRIBUTE_DISABLED__SOLVER_DIRECT_VERBOSEDATA()
#else
#define SOFA_ATTRIBUTE_DISABLED__SOLVER_DIRECT_VERBOSEDATA() \
SOFA_ATTRIBUTE_DISABLED("v23.12", "v24.06", "This Data is no longer used")
#endif // SOFA_BUILD_SOFA_COMPONENT_LINEARSOLVER_DIRECT

#ifdef SOFA_BUILD_SOFA_COMPONENT_LINEARSOLVER_DIRECT
#define SOFA_ATTRIBUTE_DEPRECATED__SPARSECOMMON()
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,6 @@ class MinResLinearSolver : public sofa::component::linearsolver::MatrixLinearSol
Data<unsigned> f_maxIter; ///< maximum number of iterations of the Conjugate Gradient solution
Data<double> f_tolerance; ///< desired precision of the Conjugate Gradient Solution (ratio of current residual norm over initial residual norm)

SOFA_ATTRIBUTE_DISABLED__SOLVER_ITERATIVE_VERBOSEDATA()
sofa::core::objectmodel::lifecycle::RemovedData f_verbose{this, "v23.12", "v24.06", "verbose", "This Data is no longer used"};

Data<std::map < std::string, sofa::type::vector<SReal> > > f_graph; ///< Graph of residuals at each iteration

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,13 +38,6 @@ namespace sofa::component::linearsolver::iterative
} // namespace sofa::component::linearsolver::iterative


#ifdef SOFA_BUILD_SOFA_COMPONENT_LINEARSOLVER_ITERATIVE
#define SOFA_ATTRIBUTE_DISABLED__SOLVER_ITERATIVE_VERBOSEDATA()
#else
#define SOFA_ATTRIBUTE_DISABLED__SOLVER_ITERATIVE_VERBOSEDATA() \
SOFA_ATTRIBUTE_DISABLED("v23.12", "v24.06", "This Data is no longer used")
#endif // SOFA_BUILD_SOFA_COMPONENT_LINEARSOLVER_ITERATIVE

#ifdef SOFA_BUILD_SOFA_COMPONENT_LINEARSOLVER_ITERATIVE
#define SOFA_ATTRIBUTE_DEPRECATED__RENAME_DATA_IN_LINEARSOLVER_ITERATIVE()
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,6 @@ class BlockJacobiPreconditioner : public sofa::component::linearsolver::MatrixLi
typedef sofa::component::linearsolver::MatrixLinearSolver<TMatrix,TVector> Inherit;
typedef typename TMatrix::Block SubMatrix;

SOFA_ATTRIBUTE_DISABLED__PRECONDITIONER_VERBOSEDATA()
sofa::core::objectmodel::lifecycle::RemovedData f_verbose{this, "v23.12", "v24.06", "verbose", "This Data is no longer used"};

protected:
BlockJacobiPreconditioner();
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,6 @@ class JacobiPreconditioner : public sofa::component::linearsolver::MatrixLinearS
typedef TVector Vector;
typedef sofa::component::linearsolver::MatrixLinearSolver<TMatrix,TVector> Inherit;

SOFA_ATTRIBUTE_DISABLED__PRECONDITIONER_VERBOSEDATA()
sofa::core::objectmodel::lifecycle::RemovedData f_verbose{this, "v23.12", "v24.06", "verbose", "This Data is no longer used"};

protected:
JacobiPreconditioner();
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,9 +109,6 @@ class PrecomputedWarpPreconditioner : public sofa::component::linearsolver::Matr

Data<bool> d_jmjt_twostep; ///< Use two step algorithm to compute JMinvJt

SOFA_ATTRIBUTE_DISABLED__PRECONDITIONER_VERBOSEDATA()
sofa::core::objectmodel::lifecycle::RemovedData f_verbose{this, "v23.12", "v24.06", "verbose", "This Data is no longer used"};

SOFA_ATTRIBUTE_DEPRECATED__RENAME_DATA_IN_LINEARSOLVER_PRECONDITIONER()
sofa::core::objectmodel::lifecycle::RenamedData<bool> jmjt_twostep;

Expand Down
Loading