Skip to content

Commit

Permalink
Fix last forgotten disabled
Browse files Browse the repository at this point in the history
  • Loading branch information
hugtalbot committed Jan 26, 2025
1 parent fefde77 commit 5019950
Show file tree
Hide file tree
Showing 59 changed files with 23 additions and 280 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +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

namespace sofa::component::collision::detection::algorithm
{
constexpr const char* MODULE_NAME = "@PROJECT_NAME@";
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 @@ -102,7 +102,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 @@ -36,12 +36,3 @@ namespace sofa::component::constraint::lagrangian::solver
constexpr const char* MODULE_NAME = "@PROJECT_NAME@";
constexpr const char* MODULE_VERSION = "@PROJECT_VERSION@";
} // namespace 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
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,8 +44,6 @@ 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;


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 @@ -90,31 +90,14 @@ class RigidMapping : public core::Mapping<TIn, TOut>, public NonLinearMappingDat
typedef sofa::linearalgebra::CompressedRowSparseMatrix<MBloc> MatrixType;

Data<OutVecCoord> d_points; ///< Local Coordinates of the points
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use d_points instead") DeprecatedAndRemoved points;

OutVecCoord m_rotatedPoints; ///< vectors from frame origin to mapped points, projected to world coordinates
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use m_rotatedPoints instead") DeprecatedAndRemoved rotatedPoints;

RigidMappingInternalData<In, Out> m_data;
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use m_data instead") DeprecatedAndRemoved data;

Data<sofa::Index> d_index; ///< input DOF index
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use d_index instead") DeprecatedAndRemoved index;

sofa::core::objectmodel::DataFileName d_fileRigidMapping; ///< Filename
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use d_fileRigidMapping instead") DeprecatedAndRemoved fileRigidMapping;

Data<bool> d_useX0; ///< Use x0 instead of local copy of initial positions (to support topo changes)
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use d_useX0 instead") DeprecatedAndRemoved useX0;

Data<bool> d_indexFromEnd; ///< input DOF index starts from the end of input DOFs vector
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use d_indexFromEnd instead") DeprecatedAndRemoved indexFromEnd;

Data< type::vector<unsigned int> > d_rigidIndexPerPoint; ///< For each mapped point, the index of the Rigid it is mapped from
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use d_rigidIndexPerPoint instead") DeprecatedAndRemoved rigidIndexPerPoint;

Data<bool> d_globalToLocalCoords; ///< are the output DOFs initially expressed in global coordinates
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use d_globalToLocalCoords instead") DeprecatedAndRemoved globalToLocalCoords;

protected:
RigidMapping();
Expand Down Expand Up @@ -173,19 +156,14 @@ class RigidMapping : public core::Mapping<TIn, TOut>, public NonLinearMappingDat
void setJMatrixBlock(sofa::Index outIdx, sofa::Index inIdx);

std::unique_ptr<MatrixType> m_matrixJ;
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use m_matrixJ instead") DeprecatedAndRemoved matrixJ;
bool m_updateJ;
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use m_updateJ instead") DeprecatedAndRemoved updateJ;

typedef linearalgebra::EigenSparseMatrix<In,Out> SparseMatrixEigen;
SparseMatrixEigen m_eigenJacobian; ///< Jacobian of the mapping used by getJs
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use m_eigenJacobian instead") DeprecatedAndRemoved eigenJacobian;
type::vector<sofa::linearalgebra::BaseMatrix*> m_eigenJacobians; /// used by getJs
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use m_eigenJacobians instead") DeprecatedAndRemoved eigenJacobians;

typedef linearalgebra::EigenSparseMatrix<In,In> StiffnessSparseMatrixEigen;
StiffnessSparseMatrixEigen m_geometricStiffnessMatrix;
SOFA_ATTRIBUTE_DISABLED("v23.06", "v23.12", "Use m_geometricStiffnessMatrix instead") DeprecatedAndRemoved geometricStiffnessMatrix;
};

template <std::size_t N, class Real>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -144,8 +144,8 @@ struct EulerImplicit_test_2_particles_to_equilibrium : public BaseSimulationTest
// run simulation

Eigen::VectorXd x0, x1, v0, v1;
x0 = component::odesolver::testing::getVector( root, core::VecId::position() ); //cerr<<"EulerImplicit_test, initial positions : " << x0.transpose() << endl;
v0 = component::odesolver::testing::getVector( root, core::VecId::velocity() );
x0 = component::odesolver::testing::getVector( root, sofa::core::vec_id::read_access::position ); //cerr<<"EulerImplicit_test, initial positions : " << x0.transpose() << endl;
v0 = component::odesolver::testing::getVector( root, sofa::core::vec_id::read_access::velocity );

Eigen::VectorXd::RealScalar dx, dv;
unsigned n=0;
Expand All @@ -154,8 +154,8 @@ struct EulerImplicit_test_2_particles_to_equilibrium : public BaseSimulationTest
do {
sofa::simulation::node::animate(root.get(), 1_sreal);

x1 = component::odesolver::testing::getVector( root, core::VecId::position() ); //cerr<<"EulerImplicit_test, new positions : " << x1.transpose() << endl;
v1 = component::odesolver::testing::getVector( root, core::VecId::velocity() );
x1 = component::odesolver::testing::getVector( root, sofa::core::vec_id::read_access::position ); //cerr<<"EulerImplicit_test, new positions : " << x1.transpose() << endl;
v1 = component::odesolver::testing::getVector( root, sofa::core::vec_id::read_access::velocity );

dx = (x0-x1).lpNorm<Eigen::Infinity>();
dv = (v0-v1).lpNorm<Eigen::Infinity>();
Expand Down Expand Up @@ -260,8 +260,8 @@ struct EulerImplicit_test_2_particles_in_different_nodes_to_equilibrium : publi
// run simulation

Eigen::VectorXd x0, x1, v0, v1;
x0 = component::odesolver::testing::getVector(root, core::VecId::position() ); //cerr<<"EulerImplicit_test, initial positions : " << x0.transpose() << endl;
v0 = component::odesolver::testing::getVector(root, core::VecId::velocity() );
x0 = component::odesolver::testing::getVector(root, sofa::core::vec_id::read_access::position ); //cerr<<"EulerImplicit_test, initial positions : " << x0.transpose() << endl;
v0 = component::odesolver::testing::getVector(root, sofa::core::vec_id::read_access::velocity );

SReal dx, dv;
unsigned n=0;
Expand All @@ -270,8 +270,8 @@ struct EulerImplicit_test_2_particles_in_different_nodes_to_equilibrium : publi
do {
sofa::simulation::node::animate(root.get(), 1_sreal);

x1 = component::odesolver::testing::getVector(root, core::VecId::position() ); //cerr<<"EulerImplicit_test, new positions : " << x1.transpose() << endl;
v1 = component::odesolver::testing::getVector(root, core::VecId::velocity() );
x1 = component::odesolver::testing::getVector(root, sofa::core::vec_id::read_access::position ); //cerr<<"EulerImplicit_test, new positions : " << x1.transpose() << endl;
v1 = component::odesolver::testing::getVector(root, sofa::core::vec_id::read_access::velocity );

dx = (x0-x1).lpNorm<Eigen::Infinity>();
dv = (v0-v1).lpNorm<Eigen::Infinity>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,6 @@ class PlasticMaterial : public BaseMaterial
public:
SOFA_CLASS(PlasticMaterial, BaseMaterial);

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

typedef sofa::type::vector<double> VecDouble;
typedef sofa::type::vector<Vec3> VecStress;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,9 +73,6 @@ class MechanicalObject : public sofa::core::behavior::MechanicalState<DataTypes>

typedef typename core::behavior::BaseMechanicalState::ConstraintBlock ConstraintBlock;

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

protected:
MechanicalObject();
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,6 @@ class SOFA_COMPONENT_TOPOLOGY_CONTAINER_CONSTANT_API CubeTopology : public MeshT
public:
SOFA_CLASS(CubeTopology,MeshTopology);

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

protected:
CubeTopology(int nx, int ny, int nz);
CubeTopology();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ class SOFA_COMPONENT_TOPOLOGY_CONTAINER_CONSTANT_API SphereQuadTopology : public
{
public:
SOFA_CLASS(SphereQuadTopology,CubeTopology);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Vector3, sofa::type::Vec3);

protected:
SphereQuadTopology(int nx, int ny, int nz);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -147,9 +147,6 @@ class HexahedronSetGeometryAlgorithms : public QuadSetGeometryAlgorithms<DataTyp

void draw(const core::visual::VisualParams* vparams) override;

SOFA_ATTRIBUTE_DISABLED("v23.12", "v23.12", "Method writeMSHfile has been disabled. To export the topology as .gmsh file, use the sofa::component::io::mesh::MeshExporter.")
void writeMSHfile(const char *filename) const {msg_deprecated() << "Method writeMSHfile has been disabled. To export the topology as " << filename << " file, use the sofa::component::io::mesh::MeshExporter."; }

protected:
Data<bool> d_showHexaIndices; ///< Debug : view Hexa indices
Data<bool> d_drawHexahedra; ///< if true, draw the Hexahedron in the topology
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,9 +101,6 @@ class QuadSetGeometryAlgorithms : public EdgeSetGeometryAlgorithms<DataTypes>

void draw(const core::visual::VisualParams* vparams) override;

SOFA_ATTRIBUTE_DISABLED("v23.12", "v23.12", "Method writeMSHfile has been disabled. To export the topology as .gmsh file, use the sofa::component::io::mesh::MeshExporter.")
void writeMSHfile(const char *filename) const {msg_deprecated() << "Method writeMSHfile has been disabled. To export the topology as " << filename << " file, use the sofa::component::io::mesh::MeshExporter."; }

protected:
Data<bool> showQuadIndices; ///< Debug : view Quad indices
Data<bool> _drawQuads; ///< if true, draw the quads in the topology
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -164,9 +164,6 @@ class TetrahedronSetGeometryAlgorithms : public TriangleSetGeometryAlgorithms<Da
void subDivideRestTetrahedronsWithPlane(sofa::type::vector<Coord>& intersectedPoints, sofa::type::vector<EdgeID>& intersectedEdgeID, Coord planePos, Coord planeNormal);
int subDivideRestTetrahedronWithPlane(TetraID tetraIdx, sofa::type::vector<EdgeID>& intersectedEdgeID, sofa::type::vector<PointID>& intersectedPointID, Coord planeNormal, sofa::type::vector<Tetra>& toBeAddedTetra);

SOFA_ATTRIBUTE_DISABLED("v23.12", "v23.12", "Method writeMSHfile has been disabled. To export the topology as .gmsh file, use the sofa::component::io::mesh::MeshExporter.")
void writeMSHfile(const char *filename) const {msg_deprecated() << "Method writeMSHfile has been disabled. To export the topology as " << filename << " file, use the sofa::component::io::mesh::MeshExporter."; }

protected:
Data<bool> d_showTetrahedraIndices; ///< Debug : view Tetrahedrons indices
Data<bool> d_drawTetrahedra; ///< if true, draw the tetrahedra in the topology
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -352,10 +352,6 @@ class TriangleSetGeometryAlgorithms : public EdgeSetGeometryAlgorithms<DataTypes
*/
virtual bool InciseAlongEdgeList(const sofa::type::vector<EdgeID>& edges, sofa::type::vector<PointID>& new_points, sofa::type::vector<PointID>& end_points, bool& reachBorder);


SOFA_ATTRIBUTE_DISABLED("v23.12", "v23.12", "Method writeMSHfile has been disabled. To export the topology as .gmsh file, use the sofa::component::io::mesh::MeshExporter.")
void writeMSHfile(const char *filename) const {msg_deprecated() << "Method writeMSHfile has been disabled. To export the topology as " << filename << " file, use the sofa::component::io::mesh::MeshExporter."; }

protected:
Data<bool> showTriangleIndices; ///< Debug : view Triangle indices
Data<bool> _draw; ///< if true, draw the triangles in the topology
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ class SOFA_COMPONENT_TOPOLOGY_CONTAINER_GRID_API CylinderGridTopology : public G
{
public:
SOFA_CLASS(CylinderGridTopology,GridTopology);
SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER(Vector3, sofa::type::Vec3);

protected:
/// Default constructor
Expand Down
Loading

0 comments on commit 5019950

Please sign in to comment.