Skip to content

Commit

Permalink
complete cleaning in Component
Browse files Browse the repository at this point in the history
  • Loading branch information
hugtalbot committed Dec 29, 2024
1 parent aca70f7 commit fc3b7d3
Show file tree
Hide file tree
Showing 19 changed files with 79 additions and 45 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@
<RequiredPlugin name="Sofa.Component.Visual"/> <!-- Needed to use components [VisualStyle] -->
<RequiredPlugin name="Sofa.GL.Component.Rendering3D"/> <!-- Needed to use components [OglModel] -->
<VisualStyle displayFlags="showForceFields showCollisionModels" />

<DefaultAnimationLoop />

<CollisionPipeline depth="6" verbose="0" draw="0" />
<BruteForceBroadPhase/>
<BVHNarrowPhase/>
Expand Down
14 changes: 7 additions & 7 deletions examples/Component/Controller/test_sleep.scn
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
<RequiredPlugin name="Sofa.Component.Visual"/> <!-- Needed to use components [VisualStyle] -->
<RequiredPlugin name="Sofa.GL.Component.Rendering3D"/> <!-- Needed to use components [OglModel] -->
<RequiredPlugin name="Sofa.GL.Component.Shader"/> <!-- Needed to use components [LightManager OglFloat3Variable OglShader SpotLight] -->
<RequiredPlugin name="SofaUserInteraction"/> <!-- Needed to use components [SleepController] -->

<VisualStyle displayFlags="" /> <!-- showInteractionForceFields -->
<FreeMotionAnimationLoop />
<GenericConstraintSolver maxIterations="1000" tolerance="0.001"/>
Expand Down Expand Up @@ -63,9 +63,9 @@
<MeshOBJLoader name="loader" filename="mesh/cube.obj" triangulate="1" />
<MeshTopology src="@loader" />
<MechanicalObject src="@loader" />
<TriangleCollisionModel contactStiffness="10.0" />
<LineCollisionModel contactStiffness="10.0" />
<PointCollisionModel contactStiffness="10.0" />
<TriangleCollisionModel />
<LineCollisionModel />
<PointCollisionModel />
<RigidMapping />
</Node>
</Node>
Expand All @@ -89,9 +89,9 @@
<MeshOBJLoader name="loader" filename="mesh/cube.obj" triangulate="1" />
<MeshTopology src="@loader" />
<MechanicalObject src="@loader" />
<TriangleCollisionModel contactStiffness="10.0" />
<LineCollisionModel contactStiffness="10.0" />
<PointCollisionModel contactStiffness="10.0" />
<TriangleCollisionModel />
<LineCollisionModel />
<PointCollisionModel />
<RigidMapping />
</Node>
</Node>
Expand Down
2 changes: 1 addition & 1 deletion examples/Component/Controller/test_sleep3.scn
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@
<TriangleCollisionModel name="FloorTriangle" simulated="0" moving="0" />
<LineCollisionModel name="FloorLine_line" simulated="0" moving="0" />
<PointCollisionModel name="FloorLine_point" simulated="0" moving="0" />
<MeshOBJLoader name="meshLoader_3" filename="mesh/floor3.obj" scaleTex="0.2 0.2" scale="1.75" handleSeams="1" />
<MeshOBJLoader name="meshLoader_3" filename="mesh/floor3.obj" scale="1.75" handleSeams="1" />
<OglModel name="FloorV" src="@meshLoader_3" texturename="textures/brushed_metal.bmp" dy="-10" />
</Node>
</Node>
2 changes: 1 addition & 1 deletion examples/Component/Engine/Generate/MergePoints.scn
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
<UniformMass totalMass="50.0" />
<HexahedronFEMForceField name="FEM" youngModulus="4000.0" poissonRatio="0.30" method="large" updateStiffnessMatrix="false" printLog="0"
drawing="1"/>
<UncoupledConstraintCorrection />
<UncoupledConstraintCorrection defaultCompliance="0.05"/>

<Node name="Visu">
<QuadSetTopologyContainer name="Container"
Expand Down
2 changes: 1 addition & 1 deletion examples/Component/Engine/Select/MeshROI.scn
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
<Node name="MeshROI" >
<MeshOBJLoader name="ROIloader" filename="mesh/malleus.obj" scale3d="1 1 1" translation="0 0 0" rotation="0 0 0"/>
<OglModel />
<MeshROI name="ROIm" drawMesh="0" drawBox="0" drawEdges="0" drawTriangles="1" drawTetrahedra="1" drawOut="0" computeMeshROI="1" doUpdate="0"
<MeshROI name="ROIm" drawBox="0" drawEdges="0" drawTriangles="1" drawTetrahedra="1" drawOut="0" computeMeshROI="1" doUpdate="0"
position="@../mecaObj.position" tetrahedra="@../loader.tetrahedra" ROIposition="@ROIloader.position" ROItriangles="@ROIloader.triangles" />
</Node>
</Node>
Expand Down
12 changes: 6 additions & 6 deletions examples/Component/Engine/Select/NearestPointROI.scn
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,14 @@
<BoxROI box="-0.1 -0.1 -0.1 3.1 3.1 0.1" name="box"/>
<FixedProjectiveConstraint indices="@box.indices"/>
<TetrahedronFEMForceField name="FEM" youngModulus="4000" poissonRatio="0.3" computeVonMisesStress="1" showVonMisesStressPerElement="true"/>
<UncoupledConstraintCorrection useOdeSolverIntegrationFactors="0"/>
<UncoupledConstraintCorrection defaultCompliance="1" useOdeSolverIntegrationFactors="0"/>
</Node>
<Node name="M2">
<MechanicalObject name="mo"/>
<UniformMass totalMass="160" />
<RegularGridTopology nx="4" ny="4" nz="10" xmin="0" xmax="3" ymin="0" ymax="3" zmin="9" zmax="18" />
<TetrahedronFEMForceField name="FEM" youngModulus="20000" poissonRatio="0.3" computeVonMisesStress="1" showVonMisesStressPerElement="true"/>
<UncoupledConstraintCorrection useOdeSolverIntegrationFactors="0"/>
<UncoupledConstraintCorrection defaultCompliance="1" useOdeSolverIntegrationFactors="0"/>
</Node>
<Node name="M3">
<MechanicalObject name="mo"/>
Expand All @@ -52,7 +52,7 @@
<BoxROI box="-0.1 -0.1 26.99 3.1 3.1 27.1" name="box"/>
<FixedProjectiveConstraint indices="@box.indices"/>
<TetrahedronFEMForceField name="FEM" youngModulus="4000" poissonRatio="0.3" computeVonMisesStress="1" showVonMisesStressPerElement="true"/>
<UncoupledConstraintCorrection useOdeSolverIntegrationFactors="0"/>
<UncoupledConstraintCorrection defaultCompliance="1" useOdeSolverIntegrationFactors="0"/>
</Node>

<NearestPointROI template="Vec3" name="np1" object1="@./M1/mo" object2="@./M2/mo" radius="0.1"/>
Expand All @@ -75,14 +75,14 @@
<BoxROI box="3.9 -0.1 -0.1 7.1 3.1 0.1" name="box"/>
<FixedProjectiveConstraint indices="@box.indices"/>
<TetrahedronFEMForceField name="FEM" youngModulus="4000" poissonRatio="0.3" computeVonMisesStress="1" showVonMisesStressPerElement="true"/>
<UncoupledConstraintCorrection useOdeSolverIntegrationFactors="0"/>
<UncoupledConstraintCorrection defaultCompliance="1" useOdeSolverIntegrationFactors="0"/>
</Node>
<Node name="M2"> <!-- This object has a higher resolution than the others -->
<MechanicalObject name="mo"/>
<UniformMass totalMass="160" />
<RegularGridTopology nx="8" ny="8" nz="20" xmin="4" xmax="7" ymin="0" ymax="3" zmin="9" zmax="18" />
<TetrahedronFEMForceField name="FEM" youngModulus="20000" poissonRatio="0.3" computeVonMisesStress="1" showVonMisesStressPerElement="true"/>
<UncoupledConstraintCorrection useOdeSolverIntegrationFactors="0"/>
<UncoupledConstraintCorrection defaultCompliance="1" useOdeSolverIntegrationFactors="0"/>
</Node>
<Node name="M3">
<MechanicalObject name="mo"/>
Expand All @@ -91,7 +91,7 @@
<BoxROI box="3.9 -0.1 26.99 7.1 3.1 27.1" name="box"/>
<FixedProjectiveConstraint indices="@box.indices"/>
<TetrahedronFEMForceField name="FEM" youngModulus="4000" poissonRatio="0.3" computeVonMisesStress="1" showVonMisesStressPerElement="true"/>
<UncoupledConstraintCorrection useOdeSolverIntegrationFactors="0"/>
<UncoupledConstraintCorrection defaultCompliance="1" useOdeSolverIntegrationFactors="0"/>
</Node>

<!--
Expand Down
11 changes: 8 additions & 3 deletions examples/Component/IO/Mesh/MeshExporter.scn
Original file line number Diff line number Diff line change
@@ -1,7 +1,12 @@
<?xml version='1.0'?>
<Node name='Root' gravity='0 0 0' time='0' animate='0' >
<?xml version='1.0'?>

<Node name='Root' gravity='0 0 0' time='0' animate='0' bbox="0 0 0 1 1 1" >
<RequiredPlugin name="Sofa.Component.IO.Mesh"/>
<RequiredPlugin name="Sofa.Component.StateContainer"/>
<RequiredPlugin name="Sofa.Component.Topology.Container.Grid"/>

<DefaultAnimationLoop/>
<RegularGridTopology name='grid' n='6 6 6' min='-10 -10 -10' max='10 10 10' p0='-30 -10 -10' computeHexaList='0'/>
<MechanicalObject name="MechaObj"/>
<MeshExporter name='exporterA' format='vtk' printLog='true' filename='outFile' exportEveryNumberOfSteps='5' position="@MechaObj.position" hexas="@grid.computeHexaList" />
</Node>
</Node>
4 changes: 3 additions & 1 deletion examples/Component/IO/Mesh/OBJExporter.scn
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,12 @@
<RequiredPlugin name="Sofa.Component.Topology.Container.Grid"/> <!-- Needed to use components [RegularGridTopology] -->
<RequiredPlugin name="Sofa.GL.Component.Rendering3D"/> <!-- Needed to use components [OglModel] -->

<DefaultAnimationLoop />

<Node name="M1">
<EulerImplicitSolver name="cg_odesolver" printLog="false" rayleighStiffness="0.1" rayleighMass="0.1" />
<SparseLDLSolver printLog="false"/>
<CGLinearSolver iterations="1000" threshold="1.0e-9" />
<CGLinearSolver tolerance="1e-5" iterations="1000" threshold="1.0e-9" />
<MechanicalObject template="Vec3d" />
<UniformMass totalMass="100" />
<RegularGridTopology nx="4" ny="4" nz="40" xmin="-9" xmax="-6" ymin="0" ymax="3" zmin="0" zmax="19" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@
<ConstantForceField forces="0 -0.1 0" />

<Node name="Triangle">
<include href="Objects/TriangleSetTopology.xml" />
<TriangleSetTopologyContainer name="Container"/>
<TriangleSetTopologyModifier />
<Tetra2TriangleTopologicalMapping input="@/Truss/Container" output="@Container" />
<TriangleCollisionModel />
<Node name="TriangleVisual">
Expand All @@ -59,9 +60,10 @@
<ConstantForceField indices="5" forces="0 0 0 -10 0 0" />
<BarycentricMapping isMechanical="true" input="@TrussMO" output="@BeamMO" />
<Node name="VisuThread">
<MechanicalObject name="Quads" />
<include href="Objects/QuadSetTopology.xml" />
<QuadSetTopologyContainer name="Container"/>
<QuadSetTopologyModifier />
<Edge2QuadTopologicalMapping nbPointsOnEachCircle="10" radius="0.005" input="@BeamMesh" output="@Container" />
<MechanicalObject name="Quads" />
<TubularMapping nbPointsOnEachCircle="10" radius="0.005" input="@BeamMO" output="@Quads" />
<Node name="VisuOgl">
<OglModel name="Visual" color="0.5 0.5 1.0" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<RequiredPlugin name="Sofa.Component.Visual"/> <!-- Needed to use components [VisualStyle] -->
<RequiredPlugin name="Sofa.GL.Component.Rendering3D"/> <!-- Needed to use components [OglModel] -->
<VisualStyle displayFlags="showBehavior showVisual" />
<CollisionPipeline depth="6" verbose="0" draw="0" />
<CollisionPipeline depth="6" draw="0" />
<BruteForceBroadPhase/>
<BVHNarrowPhase/>
<NewProximityIntersection name="Proximity" alarmDistance="0.3" contactDistance="0.2" />
Expand All @@ -39,7 +39,7 @@
<!-- <Node name="TorusRigid"> -->
<Node name="Torus">
<EulerImplicitSolver rayleighStiffness="0.1" rayleighMass="0.1" />
<CGLinearSolver iterations="50" threshold="1e-15" tolerance="1e-15" verbose="0" />
<CGLinearSolver iterations="50" threshold="1e-15" tolerance="1e-15" />
<MechanicalObject name="rigidframe" template="Rigid3" position="1 2 0 0 0 0.7 0.7" />
<UniformMass filename="BehaviorModels/torus.rigid" />
<!--<FixedProjectiveConstraint /> -->
Expand Down
1 change: 1 addition & 0 deletions examples/Component/Mapping/NonLinear/AreaMapping.scn
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<RequiredPlugin name="Sofa.Component.Topology.Container.Grid"/> <!-- Needed to use components [RegularGridTopology] -->
<RequiredPlugin name="Sofa.Component.Visual"/> <!-- Needed to use components [VisualStyle] -->
<RequiredPlugin name="Sofa.GL.Component.Rendering3D"/> <!-- Needed to use components [OglModel] -->
<RequiredPlugin name="Sofa.GL.Component.Rendering2D"/> <!-- Needed to use components [OglColorMap] -->
</Node>

<FreeMotionAnimationLoop solveVelocityConstraintFirst="true" computeBoundingBox="false" parallelODESolving="true"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<StringMeshCreator name="loader" resolution="20" scale3d="1 1 1" />

<EulerImplicitSolver />
<EigenSimplicialLLT />
<EigenSimplicialLLT template="CompressedRowSparseMatrixMat3x3d"/>

<EdgeSetTopologyContainer name="topology" position="@loader.position" edges="@loader.edges"/>
<MechanicalObject name="dofs" template="Vec3" />
Expand Down
4 changes: 2 additions & 2 deletions examples/Component/Mapping/NonLinear/DistanceMultiMapping.scn
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,8 @@

<Node name="connection">
<MechanicalObject template="Vec1" name="connectionDOF" />
<EdgeSetTopologyContainer edges="0 1"/>
<DistanceMultiMapping template="Vec3,Vec1" input="@../springs0 @../springs1" output="@connectionDOF" indexPairs="0 19 1 0" restLengths="1" geometricStiffness="0" applyRestPosition="true" computeDistance="true"/>
<EdgeSetTopologyContainer name="edgeTopo" edges="0 1"/>
<DistanceMultiMapping template="Vec3,Vec1" topology="@edgeTopo" input="@../springs0 @../springs1" output="@connectionDOF" indexPairs="0 19 1 0" restLengths="1" geometricStiffness="0" applyRestPosition="true" computeDistance="true"/>
<RestShapeSpringsForceField template="Vec1" stiffness="1"/>
</Node>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,12 @@
<RequiredPlugin name="Sofa.Component.StateContainer"/> <!-- Needed to use components [MechanicalObject] -->
<RequiredPlugin name="Sofa.Component.Visual"/> <!-- Needed to use components [VisualStyle] -->
<VisualStyle displayFlags="showBehaviorModels showMapping" />
<Node name="parent node with independent DOFs">
<!-- <EulerImplicitSolver name="ODE solver" printLog="0" verbose="0" rayleighStiffness="0.0" rayleighMass="0"/> -->

<DefaultAnimationLoop />

<Node name="parent node with independent DOFs" bbox="-10 -10 -10 10 10 10">
<StaticSolver name="ODE solver" printLog="0" />
<CGLinearSolver template="GraphScattered" name="linear solver used by implicit ODE solvers" printLog="0" verbose="0" iterations="25" tolerance="1e-5" threshold="1e-5"/>
<CGLinearSolver template="GraphScattered" name="linear solver used by implicit ODE solvers" printLog="0" iterations="25" tolerance="1e-5" threshold="1e-5"/>
<MechanicalObject template="Rigid3" />
<PartialFixedProjectiveConstraint fixedDirections="1 1 1 0 0 0" />
<UniformMass template="Rigid3" name="mass" totalMass="1.0"/>
Expand Down
19 changes: 18 additions & 1 deletion examples/Component/Mapping/NonLinear/VolumeMapping.scn
Original file line number Diff line number Diff line change
@@ -1,7 +1,24 @@
<?xml version="1.0" ?>
<Node name="root" gravity="0 -9.81 0" dt="0.02">

<CollisionPipeline name="CollisionPipeline" verbose="0"/>
<RequiredPlugin name="Sofa.Component.Collision.Detection.Algorithm"/> <!-- Needed to use components [BVHNarrowPhase,BruteForceBroadPhase,CollisionPipeline] -->
<RequiredPlugin name="Sofa.Component.Collision.Detection.Intersection"/> <!-- Needed to use components [DiscreteIntersection] -->
<RequiredPlugin name="Sofa.Component.Collision.Geometry"/> <!-- Needed to use components [SphereCollisionModel] -->
<RequiredPlugin name="Sofa.Component.Collision.Response.Contact"/> <!-- Needed to use components [CollisionResponse] -->
<RequiredPlugin name="Sofa.Component.Constraint.Projective"/> <!-- Needed to use components [FixedProjectiveConstraint] -->
<RequiredPlugin name="Sofa.Component.IO.Mesh"/> <!-- Needed to use components [MeshGmshLoader,MeshOBJLoader,SphereLoader] -->
<RequiredPlugin name="Sofa.Component.LinearSolver.Direct"/> <!-- Needed to use components [EigenSimplicialLDLT] -->
<RequiredPlugin name="Sofa.Component.Mapping.Linear"/> <!-- Needed to use components [BarycentricMapping] -->
<RequiredPlugin name="Sofa.Component.Mapping.NonLinear"/> <!-- Needed to use components [VolumeMapping] -->
<RequiredPlugin name="Sofa.Component.Mass"/> <!-- Needed to use components [DiagonalMass] -->
<RequiredPlugin name="Sofa.Component.ODESolver.Backward"/> <!-- Needed to use components [EulerImplicitSolver] -->
<RequiredPlugin name="Sofa.Component.SolidMechanics.FEM.Elastic"/> <!-- Needed to use components [TetrahedralCorotationalFEMForceField] -->
<RequiredPlugin name="Sofa.Component.SolidMechanics.Spring"/> <!-- Needed to use components [RestShapeSpringsForceField] -->
<RequiredPlugin name="Sofa.Component.StateContainer"/> <!-- Needed to use components [MechanicalObject] -->
<RequiredPlugin name="Sofa.Component.Topology.Container.Dynamic"/> <!-- Needed to use components [TetrahedronSetGeometryAlgorithms,TetrahedronSetTopologyContainer] -->
<RequiredPlugin name="Sofa.GL.Component.Rendering3D"/>

<CollisionPipeline name="CollisionPipeline" />
<DefaultAnimationLoop/>
<BruteForceBroadPhase/>
<BVHNarrowPhase/>
Expand Down
15 changes: 7 additions & 8 deletions examples/Component/Setting/ViewerSetting.scn
Original file line number Diff line number Diff line change
Expand Up @@ -25,31 +25,30 @@
<ViewerSetting resolution="800 600"/>

<VisualStyle displayFlags="showVisual " /> <!--showBehaviorModels showCollisionModels-->
<LCPConstraintSolver tolerance="1e-3" maxIt="1000" initial_guess="false" build_lcp="false" printLog="0" mu="0.2"/>
<LCPConstraintSolver tolerance="1e-3" maxIt="1000" initial_guess="false" build_lcp="false" printLog="0" mu="0.2"/>
<FreeMotionAnimationLoop />
<CollisionPipeline depth="15" verbose="0" draw="0" />
<BruteForceBroadPhase/>
<BVHNarrowPhase/>
<MinProximityIntersection name="Proximity" alarmDistance="1.5" contactDistance="1" />
<MinProximityIntersection name="Proximity" alarmDistance="1.5" contactDistance="1" />

<LightManager />
<SpotLight name="light1" color="1 1 1" position="0 80 25" direction="0 -1 -0.8" cutoff="30" exponent="1" />
<SpotLight name="light2" color="1 1 1" position="0 40 100" direction="0 0 -1" cutoff="30" exponent="1" />
<SpotLight name="light2" color="1 1 1" position="0 40 100" direction="0 0 -1" cutoff="30" exponent="1" />

<CollisionResponse name="Response" response="FrictionContactConstraint" />
<Node name="Snake" >

<SparseGridRamificationTopology n="4 12 3" fileTopology="mesh/snake_body.obj" nbVirtualFinerLevels="3" finestConnectivity="0" />
<SparseGridRamificationTopology n="4 12 3" fileTopology="mesh/snake_body.obj" nbVirtualFinerLevels="3" finestConnectivity="0" />

<EulerImplicitSolver name="cg_odesolver" rayleighMass="1" rayleighStiffness="0.03" />
<CGLinearSolver name="linear solver" iterations="20" tolerance="1e-12" threshold="1e-18" />
<MechanicalObject name="dofs" scale="1" dy="2"/>
<MechanicalObject name="dofs" scale="1" dy="2"/>
<UniformMass totalMass="1.0" />
<HexahedronFEMForceField name="FEM" youngModulus="30000.0" poissonRatio="0.3" method="large" updateStiffnessMatrix="false" printLog="0" />

<UncoupledConstraintCorrection />
<UncoupledConstraintCorrection defaultCompliance="0.001"/>

<Node name="Collis">
<Node name="Collis">
<MeshOBJLoader name="loader" filename="mesh/meca_snake_900tri.obj" />
<MeshTopology src="@loader" />
<MechanicalObject src="@loader" name="CollisModel" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
<TriangleSetTopologyContainer name="Container" />
<TriangleSetTopologyModifier />
<Tetra2TriangleTopologicalMapping input="@../Container" output="@Container" />
<BoxROI name="boxSelection" box="0 0 0 1 1 1.1" drawTriangles="true" listening="true"/>
<BoxROI name="BoxROI" position="@../Volume.position" triangles="@Container.triangles" box="-0.5 -0.5 0.9 0.5 0.5 1.1" drawTriangles="true"/>
<TriangularFEMForceField name="FEM" youngModulus="60" poissonRatio="0.3" method="large" />
<TriangularBendingSprings name="FEM-Bend" stiffness="300" damping="1.0" />
<TrianglePressureForceField triangleList="@boxSelection.triangleIndices" pressure="0.4 0 0" />
Expand Down
Loading

0 comments on commit fc3b7d3

Please sign in to comment.