Replies: 5 comments 3 replies
-
Hi @wj9991, You can use the "visualModel" in Cosserat, similar to how it is done in SOFA. The only limitation is to utilize the mapping and the global frame's node. Avoid utilizing them within the local mechanical state, I mean the node associated with the "BeamHookeLawForceField." |
Beta Was this translation helpful? Give feedback.
-
Look here https://github.com/SofaDefrost/Cosserat/blob/actuatorBranch/examples/python3/actuators/step3.py, in the function |
Beta Was this translation helpful? Give feedback.
-
I tried several versions of what I hoped would be a visualisation for a simple Cosserat rod/tube. On the one hand, I tried to map a long rod onto the Cosserat object using the CylinderGridTopology. On the other hand, I created a mesh for a hollow slendeer cylinder in Blender to map it to a Cosserat object in the same way. The results are shown below. With all options, the virtual object is displayed in the GUI, but unfortunately, as soon as the Cosserat rod bends, you can see that the models are not connected. Do you see where the error lies? Version 1: CylinderFEMNode in cosserat_frame node, CylinderGridTopology import Sofa
from useful.parameter import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters, Parameters
geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30.0, nbSection=32, nbFrames=32,
showFramesObject=1, buildCollisionModel=0)
physicsParams = BeamPhysicsParameters(beamMass=1.0, youngModulus=1.0e4, poissonRatio=0.38,
beamRadius=0.2, beamLength=30.0)
simuParams = SimulationParameters()
Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams)
stiffness_param = 1.e10
def _add_rigid_base(p_node):
rigid_base_node = p_node.addChild('rigid_base')
rigid_base_node.addObject('MechanicalObject', template="Rigid3d", name="cosserat_base_mo",
position="0 0 0 0 0 0. 1", showObject=1, showObjectScale="0.1")
rigid_base_node.addObject('RestShapeSpringsForceField', template="Rigid3d", name="spring",
stiffness=stiffness_param, angularStiffness=stiffness_param,
mstate="@cosserat_base_mo", external_points="0", points="0")
return rigid_base_node
def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=0.2):
cosserat_coordinate_node = p_node.addChild('cosseratCoordinate')
cosserat_coordinate_node.addObject('MechanicalObject', template="Vec3d", name="cosserat_state",
position=bending_states)
cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape="circular",
length=list_sections_length, radius=_radius,
youngModulus=physicsParams.youngModulus, poissonRatio=physicsParams.poissonRatio)
return cosserat_coordinate_node
#########################################################
####################### VERSION 1 #######################
#########################################################
def _add_cosserat_frame(p_node, _bending_node, nb_framesF, _section_curv_abs, _frame_curv_abs, _radius=0.2):
length=30.0
abscissa=0.0
index=0
radius=0.2
translation = [abscissa, 0., 0.]
color = 'grey'
cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node')
_bending_node.addChild(cosserat_in_Sofa_frame_node)
frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template="Rigid3d", name="FramesMO",
position=nb_framesF, showIndices=0, showObject=0, showObjectScale=0.8)
cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=physicsParams.beamMass)
cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', name="cosseratMapping",
curv_abs_input=_section_curv_abs, curv_abs_output=_frame_curv_abs,
input1=_bending_node.cosserat_state.getLinkPath(), input2=p_node.cosserat_base_mo.getLinkPath(),
output=frames_mo.getLinkPath(), debug=0, radius=_radius)
CylinderFEMNode = cosserat_in_Sofa_frame_node.addChild('CylinderFEMNode')
CylinderFEMNode.addObject('CylinderGridTopology', name="grid", nx="5", ny="5", nz="30", length=length, radius=radius, axis="1 0 0")
CylinderFEMNode.addObject('MeshTopology', src="@grid")
CylinderFEMNode.addObject('MechanicalObject', name="cylinder", template="Rigid3d", position=translation)
Visu = CylinderFEMNode.addChild('Visu')
Visu.addObject('OglModel', name="Visual", color=color)
#Visu.addObject('BarycentricMapping', input="@../../FramesMO", output="@Visual")
Visu.addObject('RigidMapping', input="@../../FramesMO", output="@Visual")
return cosserat_in_Sofa_frame_node
#########################################################
####################### VERSION 2 #######################
#########################################################
def _add_cosserat_frame(p_node, _bending_node, nb_framesF, _section_curv_abs, _frame_curv_abs, _radius=0.2):
cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node')
_bending_node.addChild(cosserat_in_Sofa_frame_node)
frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template="Rigid3d", name="FramesMO",
position=nb_framesF, showIndices=0, showObject=1, showObjectScale=0.8)
cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=physicsParams.beamMass)
cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', name="cosseratMapping",
curv_abs_input=_section_curv_abs, curv_abs_output=_frame_curv_abs,
input1=_bending_node.cosserat_state.getLinkPath(), input2=p_node.cosserat_base_mo.getLinkPath(),
output=frames_mo.getLinkPath(), debug=0, radius=_radius)
cylinder_node = cosserat_in_Sofa_frame_node.addChild('cylinder_node')
cylinder_node.addObject('MechanicalObject', template="Rigid3d", name="CylinderMO")
cylinder_node.addObject('MeshOBJLoader', name="cylinder1", filename="mesh/cylinder1.obj")
cylinder_node.addObject('OglModel', name="VisualModel", src="@cylinder1", color='red')
cylinder_node.addObject('RigidMapping', name="VisualMapping1", input="@../FramesMO", output="@VisualModel")
#cylinder_node.addObject('BarycentricMapping', name="VisualMapping2", input="@../FramesMO", output="@VisualModel")
#cylinder_node.addObject('IdentityMapping', name="VisualMapping2", input="@../FramesMO", output="@VisualModel")
return cosserat_in_Sofa_frame_node
#########################################################
####################### VERSION 3 #######################
#########################################################
def _add_cosserat_frame(p_node, _bending_node, nb_framesF, _section_curv_abs, _frame_curv_abs, _radius=0.2):
cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node')
_bending_node.addChild(cosserat_in_Sofa_frame_node)
frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template="Rigid3d", name="FramesMO",
position=nb_framesF, showIndices=0, showObject=0, showObjectScale=0.8)
cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=physicsParams.beamMass)
cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', name="cosseratMapping",
curv_abs_input=_section_curv_abs, curv_abs_output=_frame_curv_abs,
input1=_bending_node.cosserat_state.getLinkPath(), input2=p_node.cosserat_base_mo.getLinkPath(),
output=frames_mo.getLinkPath(), debug=0, radius=_radius)
return cosserat_in_Sofa_frame_node
def createCylinderNode(p_node, length=30.0, abscissa=0.0, radius=0.2, color = 'grey'):
translation = [abscissa, 0., 0.]
CylinderFEMNode = p_node.addChild('CylinderFEMNode')
CylinderFEMNode.addObject('CylinderGridTopology', name="grid", nx="20", ny="24", nz="24", length=length, radius=radius, axis="1 0 0")
CylinderFEMNode.addObject('MeshTopology', src="@grid")
CylinderFEMNode.addObject('MechanicalObject', name="cylinder", template="Rigid3d", translation=translation)
Visu = CylinderFEMNode.addChild('Visu')
Visu.addObject('OglModel', name="Visual", color=color)
Visu.addObject('RigidMapping', input="@../cylinder", output="@Visual")
def createScene(root_node):
root_node.addObject('RequiredPlugin', name="plugins", pluginName=[
"Cosserat", # Needed to use components [BeamHookeLawForceField,DiscreteCosseratMapping]
"Sofa.Component.AnimationLoop", # Needed to use components [FreeMotionAnimationLoop]
"Sofa.Component.Collision.Detection.Algorithm",
"Sofa.Component.Collision.Detection.Intersection", # Needed to use components [LocalMinDistance]
"Sofa.Component.Collision.Geometry",
"Sofa.Component.Collision.Response.Contact", # Needed to use components [RuleBasedContactManager]
"Sofa.Component.Constraint.Lagrangian.Correction", # Needed to use components [GenericConstraintCorrection]
"Sofa.Component.Constraint.Lagrangian.Solver", # Needed to use components [GenericConstraintSolver]
"Sofa.Component.Constraint.Projective", # Needed to use components [FixedConstraint]
"Sofa.Component.Engine.Select",
"Sofa.Component.IO.Mesh", # Needed to use components MeshOBJLoader, MeshSTLLoader
"Sofa.Component.ODESolver.Backward", # Needed to use components [EulerImplicitSolver]
"Sofa.Component.LinearSolver.Direct", # Needed to use components [SparseLDLSolver]
"Sofa.Component.Mapping.Linear",
"Sofa.Component.Mapping.NonLinear", # Needed to use components [RigidMapping]
"Sofa.Component.Mass", # Needed to use components [UniformMass]
"Sofa.Component.MechanicalLoad",
"Sofa.Component.MechanicalLoad",
"Sofa.Component.ODESolver.Backward",
"Sofa.Component.Playback",
"Sofa.Component.Setting", # Needed to use components [BackgroundSetting]
"Sofa.Component.SolidMechanics.FEM.Elastic",
"Sofa.Component.SolidMechanics.FEM.HyperElastic",
"Sofa.Component.SolidMechanics.Spring", # Needed to use components [RestShapeSpringsForceField]
"Sofa.Component.StateContainer", # Needed to use components [MechanicalObject]
"Sofa.Component.Topology.Container.Constant", # Needed to use components [MeshTopology]
"Sofa.Component.Topology.Container.Dynamic",
"Sofa.Component.Topology.Container.Grid", # Needed to use components [RegularGridTopology]
"Sofa.Component.Topology.Mapping", # Needed to use components [Edge2QuadTopologicalMapping]
"Sofa.Component.Visual", # Needed to use components [VisualStyle]
"Sofa.GL.Component.Rendering3D", # Needed to use components [OglGrid, OglModel]
"Sofa.GUI.Component"])
root_node.addObject('VisualStyle', displayFlags="showVisualModels showBehaviorModels")# showMechanicalMappings")
root_node.gravity = [0.0, -9.18, 0.0]
root_node.dt = 0.01
root_node.addObject('FreeMotionAnimationLoop')
root_node.addObject('EulerImplicitSolver', firstOrder="0", rayleighStiffness="0.0", rayleighMass="0.0")
root_node.addObject('GenericConstraintSolver', maxIterations="500", tolerance="1e-20", computeConstraintForces=1, printLog="0")
root_node.addObject('SparseLDLSolver', name="solver", template="CompressedRowSparseMatrixd")
base_node = _add_rigid_base(root_node)
nb_sections = geoParams.nbSection
beam_length = geoParams.beamLength
length_s = beam_length/float(nb_sections)
bending_states = []
list_sections_length = []
temp = 0.0
section_curv_abs = [0.0]
for i in range(nb_sections):
bending_states.append([0, 0.0, 0.0])
list_sections_length.append((((i+1)*length_s)-i*length_s))
temp += list_sections_length[i]
section_curv_abs.append(temp)
bending_states[nb_sections-1] = [0, 0.0, 0.5]
bending_states[nb_sections-2] = [0, 0.0, 0.0]
section_curv_abs[nb_sections] = beam_length
bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length)
nb_frames = geoParams.nbFrames
length_f = beam_length/float(nb_frames)
cosserat_G_frames = []
frames_curv_abs = []
cable_position_f = []
x, y, z = 0, 0, 0
for i in range(nb_frames):
sol = i * length_f
cosserat_G_frames.append([sol + x, y, z, 0, 0, 0, 1])
cable_position_f.append([sol + x, y, z])
frames_curv_abs.append(sol + x)
cosserat_G_frames.append([beam_length + x, y, z, 0, 0, 0, 1])
cable_position_f.append([beam_length + x, y, z])
frames_curv_abs.append(beam_length + x)
_add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs)
return root_node |
Beta Was this translation helpful? Give feedback.
-
|
Beta Was this translation helpful? Give feedback.
-
|
Beta Was this translation helpful? Give feedback.
-
In SOFA each object has a mechanical model, a visual model and a collision model. In the Cosserat plugin, each Cosserat rod now has a mechanical model (or you can only display the mechanical mapping in the GUI). Unfortunately, this seems to be the case with all the Python files I have seen (such as NeedleInsertion or the tutorials). Is it even possible to create something like a visual model here, and are there any examples? Or how would that work? I'm also wondering about the role of radius and beam_radius. I wonder if they have different influences, e.g. on calculation and visualisation?
Beta Was this translation helpful? Give feedback.
All reactions