Skip to content

Commit

Permalink
Enhance FEM object integration and update beam parameters
Browse files Browse the repository at this point in the history
Modify addFEMObject function to return solver and points nodes
Update beam parameters in tutorial scenes (tuto_3, tuto_4, tuto_5)
Refactor FEM object creation in tuto_5 scene
Adjust cable constraint parameters and mapping in tuto_5
Minor code cleanup and parameter naming consistency improvements
  • Loading branch information
adagolodjo committed Oct 16, 2024
1 parent 368f0d2 commit 07fa31e
Show file tree
Hide file tree
Showing 4 changed files with 32 additions and 28 deletions.
6 changes: 4 additions & 2 deletions examples/python3/useful/header.py
Original file line number Diff line number Diff line change
Expand Up @@ -153,8 +153,8 @@ def addSolverNode(parent_node, name='solverNode', template='CompressedRowSparseM
return solver_node


def addFEMObject(parent_node, path):
finger_solver = addSolverNode(parent_node)
def addFEMObject(parent_node, path, name='FEMFinger'):
finger_solver = addSolverNode(parent_node, name=name)

# Load a VTK tetrahedral mesh and expose the resulting topology in the scene .
loader = finger_solver.addObject('MeshVTKLoader', name='loader', filename=f'{path}finger.vtk',
Expand Down Expand Up @@ -188,6 +188,8 @@ def addFEMObject(parent_node, path):
showIndices="1")
fem_points.addObject('BarycentricMapping')

return finger_solver, fem_points


def addMappedPoints(parent_node, name="pointsInFEM", position=None, showObject="1",
showIndices="1", femPos="0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"):
Expand Down
2 changes: 1 addition & 1 deletion tutorial/tuto_scenes/tuto_3.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
from useful.params import BeamPhysicsParametersNoInertia, BeamGeometryParameters
from cosserat.CosseratBase import CosseratBase

geoParams = BeamGeometryParameters(beam_length=30., nb_section=2, nb_frames=12, build_collision_model=0)
geoParams = BeamGeometryParameters(beam_length=30., nb_section=32, nb_frames=32, build_collision_model=0)
physicsParams = BeamPhysicsParametersNoInertia(beam_mass=0.3, young_modulus=1.0e3, poisson_ratio=0.38, beam_radius=1.,
beam_length=30)
Params = Parameters(beam_geo_params=geoParams, beam_physics_params=physicsParams)
Expand Down
3 changes: 2 additions & 1 deletion tutorial/tuto_scenes/tuto_4.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,8 @@
geoParams = BeamGeometryParameters(beam_length=30.,
nb_section=_nb_section, nb_frames=_nb_section, build_collision_model=0)
physicsParams = BeamPhysicsParametersNoInertia(beam_mass=1., young_modulus=1.0e4, poisson_ratio=0.38,
beam_radius=_beam_radius, beam_length=30)
beam_radius=_beam_radius, beam_length=_beam_length)

simuParams = SimulationParameters()
Params = Parameters(beam_geo_params=geoParams, beam_physics_params=physicsParams, simu_params=simuParams)

Expand Down
49 changes: 25 additions & 24 deletions tutorial/tuto_scenes/tuto_5.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
__copyright__ = "(c) 2021,Inria"
__date__ = "October, 26 2021"

from useful.header import addHeader, addSolverNode, Finger
from useful.header import addHeader, addSolverNode, addFEMObject
from useful.params import BeamPhysicsParametersNoInertia, BeamGeometryParameters, SimulationParameters
from useful.params import Parameters
from cosserat.CosseratBase import CosseratBase
Expand All @@ -19,21 +19,21 @@
import os
from math import pi
from controller import FingerController
from numpy import array


_beam_radius = 0.5
_beam_length = 81.
_nb_section = 32
force_null = [0., 0., 0., 0., 0., 0.] # N
path = f'{os.path.dirname(os.path.abspath(__file__))}/../../examples/python3/actuators/mesh/'

geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=81., showFramesObject=1,
nbSection=12, nbFrames=32, buildCollisionModel=0)
physicsParams = BeamPhysicsParametersNoInertia(beamMass=1., youngModulus=5.e6, poissonRatio=0.4, beamRadius=0.5,
beamLength=30)
geoParams = BeamGeometryParameters(beam_length=_beam_length, nb_section=_nb_section, nb_frames=_nb_section)
physicsParams = BeamPhysicsParametersNoInertia(beam_mass=1., young_modulus=5.e6, poisson_ratio=0.4,
beam_radius=_beam_radius, beam_length=_beam_length)

simuParams = SimulationParameters()
Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams)
Params = Parameters(beam_geo_params=geoParams, beam_physics_params=physicsParams, simu_params=simuParams)

force_null = [0., 0., 0., 0., 0., 0.] # N
femPos = [[0.0, 0, 0], [15, 0, 0], [30, 0, 0], [45, 0, 0], [60, 0, 0], [66, 0, 0], [81, 0.0, 0.0]]
femPos = [[0.0, 0, 0], [15., 0, 0], [30., 0, 0], [45., 0, 0], [60., 0, 0], [66., 0, 0], [81., 0.0, 0.0]]


class ForceController(Sofa.Core.Controller):
Expand All @@ -44,7 +44,7 @@ def __init__(self, *args, **kwargs):
self.force_type = kwargs['force_type']
self.tip_controller = kwargs['tip_controller']

self.size = geoParams.nbFrames
self.size = geoParams.nb_frames
self.applyForce = True
self.forceCoeff = 0.
self.theta = 0.1
Expand All @@ -69,7 +69,7 @@ def compute_force(self):
for i, v in enumerate(vec):
force[0][i] = v

def compute_orthogonal_force(self):
def compute_orthogonal_force(self) -> None:
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
# Calculate the direction of the force in order to remain orthogonal to the x axis of the last frame of the beam.
Expand All @@ -80,13 +80,13 @@ def compute_orthogonal_force(self):
for count in range(3):
force[0][count] = vec[count]

def rotate_force(self):
def rotate_force(self) -> None:
if self.forceCoeff <= 100. * pi:
with self.tip_controller.position.writeable() as position:
last_frame = self.frames.position[self.size]
vec = Quat(last_frame[3], last_frame[4], last_frame[5], last_frame[6]) # get the orientation

vec.rotateFromEuler([self.theta, 0., 0.]) # apply rotation arround x-axis
vec.rotateFromEuler([self.theta, 0., 0.]) # apply rotation around x-axis
vec.normalize()
for i, v in enumerate(vec):
position[0][i + 3] = v
Expand All @@ -100,10 +100,10 @@ def onKeypressedEvent(self, event):


def createScene(root_node):
addHeader(root_node, isConstrained=True)
addHeader(root_node, is_constrained=True)
root_node.gravity = [0, 0., 0.]

solver_node = addSolverNode(root_node, name="solver_node", isConstrained=True)
solver_node = addSolverNode(root_node, name="cable_node", isConstrained=True)

# create cosserat Beam
cosserat_beam = solver_node.addChild(CosseratBase(parent=solver_node, params=Params))
Expand All @@ -112,13 +112,15 @@ def createScene(root_node):
# Finger node
femFingerNode = root_node.addChild('femFingerNode')
""" Add FEM finger to the scene"""
finger_node, fem_points_node = Finger(femFingerNode, name="Finger", rotation=array([0.0, 180.0, 0.0]),
translation=array([-17.5, -12.5, 7.5]), path=path)
# finger_node, fem_points_node = Finger(femFingerNode, name="Finger", rotation=array([0.0, 180.0, 0.0]),
# translation=array([-17.5, -12.5, 7.5]), path=path)

finger_node, fem_points_node = addFEMObject(root_node, path=path, name="Finger")

# This creates a new node in the scene. This node is appended to the finger's node.
cable_state_node = cosserat_frames_node.addChild('cable_state_node')

# This creates a MechanicalObject, a componante holding the degree of freedom of our
# This creates a MechanicalObject, a component holding the degree of freedom of our
# mechanical modelling. In the case of a cable it is a set of positions specifying
# the points where the cable is passing by.
cable_state = cable_state_node.addObject('MechanicalObject', name="cablePos",
Expand All @@ -129,20 +131,19 @@ def createScene(root_node):
distance_node = cable_state_node.addChild('distance_node')
fem_points_node.addChild(distance_node)
distance = distance_node.addObject('MechanicalObject', template='Vec3d', position=femPos,
name="distancePointsMO", showObject='1', showObjectScale='1')

name="distancePointsMO", showObject='1', showObjectScale='1')

"""The controller of the cable is added to the scene"""
cable_state_node.addObject(FingerController(cosserat_beam.rigidBaseNode.RigidBaseMO,
cosserat_beam.cosseratCoordinateNode.cosseratCoordinateMO))
cosserat_beam.cosseratCoordinateNode.cosseratCoordinateMO))

inputCableMO = cable_state.getLinkPath()
inputFEMCableMO = fem_points_node.getLinkPath()
outputPointMO = distance.getLinkPath()
""" This constraint is used to compute the distance between the cable and the fem points"""
distance_node.addObject('QPSlidingConstraint', name="QPConstraint")
distance_node.addObject('DifferenceMultiMapping', name="pointsMulti", input1=inputFEMCableMO, indices="5",
input2=inputCableMO, output=outputPointMO, direction="@../../FramesMO.position")
distance_node.addObject('DifferenceMultiMapping', name="pointsMulti", input1=inputFEMCableMO, indices="6",
input2=inputCableMO, output=outputPointMO, direction="@../../FramesMO.position")

return root_node
# # this constance force is used only in the case we are doing force_type 1 or 2
Expand Down

0 comments on commit 07fa31e

Please sign in to comment.