Skip to content

Commit

Permalink
Merge branch 'master' into update_python_prefabs
Browse files Browse the repository at this point in the history
  • Loading branch information
adagolodjo committed Dec 4, 2024
2 parents 4c51481 + e5505ac commit 842af40
Show file tree
Hide file tree
Showing 12 changed files with 45 additions and 66 deletions.
9 changes: 4 additions & 5 deletions examples/python3/NeedleInsertion.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
from cosserat.usefulFunctions import pluginList
from cosserat.createFemRegularGrid import createFemCubeWithParams
from cosserat.cosseratObject import Cosserat
from cosserat.utils import addConstraintPoint
from useful.utils import addConstraintPoint
import sys

# params = NeedleParameters()
Expand Down Expand Up @@ -57,10 +57,9 @@ def createScene(rootNode):
solverNode.addObject('SparseLDLSolver', name='solver', template="CompressedRowSparseMatrixd")
solverNode.addObject('GenericConstraintCorrection')

needle = solverNode.addChild(
Cosserat(parent=solverNode, cosseratGeometry=needleGeometryConfig, radius=GeometryParams.radius,
name="needle", youngModulus=PhysicsParams.youngModulus, poissonRatio=PhysicsParams.poissonRatio,
rayleighStiffness=PhysicsParams.rayleighStiffness))
needle = Cosserat(parent=solverNode, cosseratGeometry=needleGeometryConfig, radius=GeometryParams.radius,
name="needle", youngModulus=PhysicsParams.youngModulus, poissonRatio=PhysicsParams.poissonRatio,
rayleighStiffness=PhysicsParams.rayleighStiffness)
needleCollisionModel = needle.addPointCollisionModel("needleCollision")

# These state is mapped on the needle and used to compute the distance between the needle and the
Expand Down
13 changes: 6 additions & 7 deletions examples/python3/PCS_Example2.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,11 +52,11 @@ def __init__(self, *args, **kwargs):
position = self.frames.position[self.size] # get the last rigid of the cosserat frame
orientation = Quat(position[3], position[4], position[5], position[6]) # get the orientation
# Get the force direction in order to remain orthogonal to the last section of beam
with self.forceNode.force.writeable() as force:
with self.forceNode.forces.writeable() as force:
vec = orientation.rotate([0., self.forceCoeff, 0.])
# print(f' The new vec is : {vec}')
for count in range(3):
force[count] = vec[count]
force[0][count] = vec[count]
if self.forceCoeff < 13.1e4:
self.forceCoeff += 100
else:
Expand Down Expand Up @@ -88,15 +88,14 @@ def createScene(rootNode):
solverNode.addObject('SparseLDLSolver', name='solver', template="CompressedRowSparseMatrixd")

needCollisionModel = 0 # use this if the collision model if the beam will interact with another object
PCS_Cosserat = solverNode.addChild(
Cosserat(parent=solverNode, cosseratGeometry=nonLinearConfig, useCollisionModel=needCollisionModel,
inertialParams=inertialParams, name="cosserat", radius=Rb, youngModulus=YM))
PCS_Cosserat = Cosserat(parent=solverNode, cosseratGeometry=nonLinearConfig, useCollisionModel=needCollisionModel,
inertialParams=inertialParams, name="cosserat", radius=Rb, youngModulus=YM, showObject="1")

beamFrame = PCS_Cosserat.cosseratFrame

constForce = beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=0.0,
indices=nonLinearConfig['nbFramesF'], force=F1)
indices=nonLinearConfig['nbFramesF'], forces=F1)

solverNode.addObject(ForceController(parent=solverNode, cosseratFrames=beamFrame.FramesMO, forceNode=constForce))
solverNode.addObject(ForceController(parent=solverNode, name='forceController', cosseratFrames=beamFrame.FramesMO, forceNode=constForce))

return rootNode
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,13 @@

import Sofa
from cosserat.cosseratObject import Cosserat
# from cosserat.nonLinearCosserat import NonLinearCosserat as nonCosserat
from cosserat.usefulFunctions import buildEdges, pluginList, BuildCosseratGeometry
from math import sqrt

# @todo ================ Unit: N, m, Kg, Pa ================
from splib3.numerics import Quat

LegendrePolyOrder = 5
# initialStrain = [[0., 0., 0], [0., 0., 0], [0., 0., 0]]
initialStrain = [[0., 0., 0], [0., 0., 0],
[0., 0., 0], [0., 0., 0], [0., 0., 0]]
YM = 4.015e8
Expand Down Expand Up @@ -52,11 +50,10 @@ def onAnimateEndEvent(self, event):
orientation = Quat(
position[3], position[4], position[5], position[6])
# Get the force direction in order to remain orthogonal to the last section of beam
with self.forceNode.force.writeable() as force:
with self.forceNode.forces.writeable() as force:
vec = orientation.rotate([0., self.forceCoeff, 0.])
# print(f' The new vec is : {vec}')
for count in range(3):
force[count] = vec[count]
force[0][count] = vec[count]

def onKeypressedEvent(self, event):
key = event['key']
Expand Down Expand Up @@ -91,12 +88,12 @@ def createScene(rootNode):
Cosserat(parent=solverNode, cosseratGeometry=nonLinearConfig, useCollisionModel=needCollisionModel,
inertialParams=inertialParams, name="cosserat", radius=Rb, youngModulus=YM))

beamFrame = nonLinearCosserat.cosseratFrame
beamFrame = PCS_Cosserat.cosseratFrame

constForce = beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=0.02,
indices=nonLinearConfig['nbFramesF'], force=F1)
indices=nonLinearConfig['nbFramesF'], forces=F1)

nonLinearCosserat = solverNode.addObject(
solverNode.addObject(
ForceController(parent=solverNode, cosseratFrames=beamFrame.FramesMO, forceNode=constForce))

# ----------------
Expand Down
11 changes: 5 additions & 6 deletions examples/python3/PNLS_Example1.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,10 +52,10 @@ def __init__(self, *args, **kwargs):

def onAnimateEndEvent(self, event):
if self.applyForce:
with self.forceNode.force.writeable() as force:
with self.forceNode.forces.writeable() as force:
vec = [0., 0., 0., 0., (self.forceCoeff * 1.) / sqrt(2), (self.forceCoeff * 1.) / sqrt(2)]
for i, v in enumerate(vec):
force[i] = v
force[0][i] = v
# print(f' The new force: {force}')

def onKeypressedEvent(self, event):
Expand Down Expand Up @@ -85,18 +85,17 @@ def createScene(rootNode):
solverNode.addObject('SparseLDLSolver', name='solver', template="CompressedRowSparseMatrixd")

needCollisionModel = 0 # use this if the collision model if the beam will interact with another object
nonLinearCosserat = solverNode.addChild(
nonCosserat(parent=solverNode, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams,
nonLinearCosserat = nonCosserat(parent=solverNode, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams,
useCollisionModel=needCollisionModel, name="cosserat", radius=Rb, youngModulus=YM,
legendreControlPoints=initialStrain, poissonRatio=PR,order=LegendrePolyOrder,
rayleighStiffness=rayleighStiffness,
activatedMMM=False))
activatedMMM=False)
cosseratNode = nonLinearCosserat.legendreControlPointsNode

beamFrame = nonLinearCosserat.cosseratFrame

constForce = beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-8,
indices=nonLinearConfig['nbFramesF'], force=F1)
indices=nonLinearConfig['nbFramesF'], forces=F1)

nonLinearCosserat = solverNode.addObject(
ForceController(parent=solverNode, cosseratFrames=beamFrame.FramesMO, forceNode=constForce))
Expand Down
11 changes: 5 additions & 6 deletions examples/python3/PNLS_Example2.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,11 +52,11 @@ def onAnimateEndEvent(self, event):
position = self.frames.position[self.size] # get the last rigid of the cosserat frame
orientation = Quat(position[3], position[4], position[5], position[6]) # get the orientation
# Get the force direction in order to remain orthogonal to the last section of beam
with self.forceNode.force.writeable() as force:
with self.forceNode.forces.writeable() as force:
vec = orientation.rotate([0., self.forceCoeff, 0.])
# print(f' The new vec is : {vec}')
for count in range(3):
force[count] = vec[count]
force[0][count] = vec[count]
if self.forceCoeff < 13.1e4:
self.forceCoeff += 100
else:
Expand Down Expand Up @@ -87,17 +87,16 @@ def createScene(rootNode):
solverNode.addObject('SparseLDLSolver', name='solver', template="CompressedRowSparseMatrixd")

needCollisionModel = 0 # use this if the collision model if the beam will interact with another object
nonLinearCosserat = solverNode.addChild(
nonCosserat(parent=solverNode, cosseratGeometry=nonLinearConfig, useCollisionModel=needCollisionModel,
nonLinearCosserat = nonCosserat(parent=solverNode, cosseratGeometry=nonLinearConfig, useCollisionModel=needCollisionModel,
name="cosserat", radius=Rb, youngModulus=YM, legendreControlPoints=initialStrain,
order=LegendrePolyOrder, inertialParams=inertialParams,
activatedMMM=True))
activatedMMM=True, showObject="1")
cosseratNode = nonLinearCosserat.legendreControlPointsNode

beamFrame = nonLinearCosserat.cosseratFrame

constForce = beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-5,
indices=nonLinearConfig['nbFramesF'], force=F1)
indices=nonLinearConfig['nbFramesF'], forces=F1)

nonLinearCosserat = solverNode.addObject(
ForceController(parent=solverNode, cosseratFrames=beamFrame.FramesMO, forceNode=constForce))
Expand Down
2 changes: 1 addition & 1 deletion examples/python3/PNLS_Example3.py
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ def createScene(rootNode):
cosseratNode = nonLinearCosserat.legendreControlPointsNode

constForce = beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-9,
indices=nonLinearConfig['nbFramesF'], force=F1)
indices=nonLinearConfig['nbFramesF'], forces=F1)

nonLinearCosserat = solverNode.addObject(
ForceController(parent=solverNode, cosseratFrames=beamFrame.FramesMO, controller=controlMo))
Expand Down
17 changes: 6 additions & 11 deletions examples/python3/cosserat/cosseratObject.py
Original file line number Diff line number Diff line change
Expand Up @@ -348,10 +348,7 @@ def createScene(rootNode):
rootNode.addObject(
"RequiredPlugin",
name="plugins",
pluginName=[
pluginList,
["SofaEngine", "SofaLoader", "SofaSimpleFem", "SofaExporter"],
],
pluginName=pluginList,
)
rootNode.addObject(
"VisualStyle",
Expand All @@ -376,13 +373,11 @@ def createScene(rootNode):
)
solverNode.addObject("GenericConstraintCorrection")

cosserat = solverNode.addChild(
Cosserat(
parent=solverNode,
cosseratGeometry=cosserat_config,
name="cosserat",
radius=0.15,
)
cosserat = Cosserat(
parent=solverNode,
cosseratGeometry=cosserat_config,
name="cosserat",
radius=0.15,
)

# use this to add the collision if the beam will interact with another object
Expand Down
2 changes: 1 addition & 1 deletion examples/python3/cosserat/needle/needleController.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import Sofa
import Cosserat
from cosserat.needle.params import ConstraintsParams
from cosserat.utils import computePositiveAlongXDistanceBetweenPoints, computeNegativeAlongXDistanceBetweenPoints
from useful.utils import computePositiveAlongXDistanceBetweenPoints, computeNegativeAlongXDistanceBetweenPoints


class Animation(Sofa.Core.Controller):
Expand Down
17 changes: 8 additions & 9 deletions examples/python3/cosserat/nonLinearCosserat.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class NonLinearCosserat(Sofa.Prefab):
Cosserat Mapping // it allow the transfer from the local to the global frame
}
"""
properties = [
prefabParameters = [
{'name': 'name', 'type': 'string', 'help': 'Node name', 'default': 'Cosserat'},
{'name': 'position', 'type': 'Rigid3d::VecCoord', 'help': 'Cosserat base position',
'default': [[0., 0., 0., 0, 0, 0, 1.]]},
Expand All @@ -67,7 +67,7 @@ class NonLinearCosserat(Sofa.Prefab):
'default': 0.0},
{'name': 'attachingToLink', 'type': 'string', 'help': 'a rest shape force field will constraint the object '
'to follow arm position', 'default': '1'},
{'name': 'showObject', 'type': 'string', 'help': ' Draw object arrow ', 'default': '0'}]
{'name': 'showObject', 'type': 'string', 'help': ' Draw object arrow ', 'default': '1'}]

def __init__(self, *args, **kwargs):
Sofa.Prefab.__init__(self, *args, **kwargs)
Expand Down Expand Up @@ -193,11 +193,11 @@ def addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF):

def createScene(rootNode):
rootNode.addObject('RequiredPlugin', name='plugins', pluginName=[pluginList,
['SofaEngine', 'SofaLoader', 'SofaSimpleFem',
'SofaExporter']])
['Sofa.Component.Visual']])
rootNode.addObject('VisualStyle', displayFlags='showVisualModels showBehaviorModels hideCollisionModels '
'hideBoundingCollisionModels hireForceFields '
'hideBoundingCollisionModels hideForceFields '
'hideInteractionForceFields hideWireframe')
rootNode.addObject('DefaultAnimationLoop')
rootNode.findData('dt').value = 0.01
# rootNode.findData('gravity').value = [0., -9.81, 0.]
rootNode.findData('gravity').value = [0., 0., 0.]
Expand All @@ -213,12 +213,11 @@ def createScene(rootNode):
# solverNode.addObject('CGLinearSolver', tolerance=1.e-12, iterations=1000, threshold=1.e-18)

needCollisionModel = 0 # use this if the collision model if the beam will interact with another object
nonLinearCosserat = solverNode.addChild(
NonLinearCosserat(parent=solverNode, cosseratGeometry=nonLinearConfig, useCollisionModel=needCollisionModel,
name="cosserat", radius=0.1, legendreControlPoints=initialStrain, order=3))
nonLinearCosserat = NonLinearCosserat(parent=solverNode, cosseratGeometry=nonLinearConfig,
useCollisionModel=needCollisionModel, name="cosserat", radius=0.1, legendreControlPoints=initialStrain, order=3)

beamFrame = nonLinearCosserat.cosseratFrame
beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-8, indices=12,
force=[0., 0., 0., 0., 0., 450.])
forces=[0., 0., 0., 0., 0., 450.])

return rootNode
4 changes: 1 addition & 3 deletions examples/python3/tutorial/formation/chiba/Actuator.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,6 @@
from fingerController import FingerController #for keyboard controlling
#from timerreset import FingerController #Uncomment to perform timed measurements(increases of 5kPa every 2 seconds)
from loopstest_function_param3 import looptest #algorithm for generating the fiber loops
import gmsh



def createScene(rootNode):
Expand Down Expand Up @@ -83,7 +81,7 @@ def createScene(rootNode):
fiber.addObject('MeshTopology', name='lines', lines=[[i, i + 1] for i in range(loopnum)])

#fiber.addObject("FixedConstraint", name="FixedConstragetLinkPathint", indices=[0])
fiber.addObject("StiffSpringForceField", template="Vec3d", name="springs", showArrowSize=0.5, drawMode=1,
fiber.addObject("SpringForceField", template="Vec3d", name="springs", showArrowSize=0.5, drawMode=1,
stiffness=Ks, damping=Kd, indices1=indices1, indices2=indices2, lengths=lengths)

# Mapping
Expand Down
3 changes: 1 addition & 2 deletions examples/python3/tutorial/formation/chiba/actuator_v1.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
import Sofa
from fingerController import FingerController # for keyboard controlling
from loopstest_function_param3 import looptest # algorithm for generating the fiber loops
import gmsh

from useful.header import addHeader, addSolverNode

Expand Down Expand Up @@ -73,7 +72,7 @@ def createScene(root_node):
showObject=True, showObjectScale=1)
hitching.addObject('MeshTopology', name='lines',
lines=[[i, i + 1] for i in range(num_loops - 1)])
hitching.addObject("StiffSpringForceField", template="Vec3d", name="springs", showArrowSize=0.5, drawMode=1,
hitching.addObject("SpringForceField", template="Vec3d", name="springs", showArrowSize=0.5, drawMode=1,
stiffness=Ks, damping=Kd, indices1=[0, 1, 2, 3, 4, 5, 6], indices2=[1, 2, 3, 4, 5, 6, 7],
lengths=loop_distance)
hitching.addObject('BarycentricMapping', name='mapping')
Expand Down
9 changes: 2 additions & 7 deletions src/Cosserat/mapping/LegendrePolynomialsMapping.inl
Original file line number Diff line number Diff line change
Expand Up @@ -42,14 +42,12 @@ namespace sofa::component::mapping {
m_matOfCoeffs.clear();
auto curvAbs = d_vectorOfCurvilinearAbscissa.getValue();
auto sz = curvAbs.size();
// std::cout << " curvAbs :" << curvAbs << std::endl;
for (unsigned int i = 1; i < sz; i++){
type::vector<double> coeffsOf_i;
coeffsOf_i.clear();
for (unsigned int order = 0; order < d_order.getValue(); order++)
coeffsOf_i.push_back(legendrePoly(order, curvAbs[i]));

// std::cout << " = = = >coeffsOf_i: " << coeffsOf_i << std::endl;
m_matOfCoeffs.push_back(coeffsOf_i);
}
}
Expand All @@ -58,10 +56,10 @@ namespace sofa::component::mapping {
template <class TIn, class TOut>
void LegendrePolynomialsMapping<TIn, TOut>::init()
{
Inherit1::init();

//Compute the coefficients for each curv_abs at all orders of the polynomials
reinit();

Inherit1::init();
}


Expand All @@ -73,16 +71,13 @@ namespace sofa::component::mapping {
const auto sz = d_vectorOfCurvilinearAbscissa.getValue().size();
out.resize(sz-1);

// std::cout<< "Apply : in " << in[0] <<std::endl;
for (unsigned int i = 0; i < sz-1; i++){
type::Vec3 Xi ;
for (unsigned int j = 0; j < in.size(); j++)
Xi += m_matOfCoeffs[i][j] * in[j];

// std::cout << " Xi : "<< Xi << std::endl;
out[i] = Xi;
}
// std::cout<< " " << std::endl;
}

template <class TIn, class TOut>
Expand Down

0 comments on commit 842af40

Please sign in to comment.