Home › Forum › SOFA › Programming with SOFA › BilateralInteractionConstraint causes unrealistic motion
- This topic has 4 replies, 2 voices, and was last updated 3 years, 2 months ago by Hugo.
-
AuthorPosts
-
16 August 2021 at 20:04 #20171AudreyModerator
Hello,
We are having an issue in which we think a BilateralInteractionConstraint causes our modeled system to move unrealistically. We are trying to attach pressurized soft robotic actuators to a central component, and yet when they pressurize, the system floats above the floor. Individual soft actuators do not float when modelled.
We have tried:
– Almost every possible combination of different solvers (now using Euler Implicit)
– Changing the time step (presently dt=0.01) — lowering the time step makes the problem appear earlier.
– Refining meshes – does not reduce or eliminate the issue.After discussion we have also tried:
– Updating Poisson ratio of the actuator to 0.45 from 0.05 (which was the value given here: https://github.com/SofaDefrost/ModelOrderReduction/blob/master/tools/sofa_test_scene/quadruped.py). This did not resolve the issue.
– Ensuring that our system of units is consistent. We have used kg, mm, s –> mN, kPaCode is below:
test.pyfrom robot import DiskWithLegs from scene import Scene import numpy as np from splib import animation DURATION = 5.0 AMPLITUDE = 100 FREQ = 0.25 PHASE = 1.0 def controller(robot, factor): t = DURATION * factor def get_pressure(t): return AMPLITUDE/2 + AMPLITUDE/2 * np.cos(2 * np.pi * FREQ * t + np.pi) pressures = [ get_pressure(t), get_pressure(max(0., t - PHASE)) ] robot.act(pressures) def createScene(rootNode): Scene(rootNode) robot = DiskWithLegs([0.0, 180.0]) robot.load(rootNode) animation.AnimationManager(rootNode) animation.animate(controller, {'robot': robot}, duration=DURATION, mode="loop") return rootNode
robot.py
from __future__ import print_function import os import numpy as np class Pneunet(): mesh_dir = './meshes' poissonRatio = 0.05 youngModulus = 96626 mass = 0.042 paperPoissonRatio = 0.49 paperYoungModulus = 5380343 friction_coef = 0.7 def __init__(self, angle=0.0): self.angle = '{:04d}'.format(int(10 * angle)) self.bank_dir = self.mesh_dir + "/pneunet_" + self.angle self.body_ym = self.youngModulus self.paper_ym = self.paperYoungModulus def act(self, pressure): self.cavity_node.pressure_constraint.value = pressure def load(self, root): self.root = root.createChild('leg'+self.angle+'Node') self.node = self.root.createChild('legNode') self.node.createObject('EulerImplicitSolver', name='odesolver', firstOrder="false", rayleighStiffness='0.1', rayleighMass='0.1') self.node.createObject('SparseLDLSolver', name="preconditioner", template='CompressedRowSparseMatrix3d') self.node.createObject( 'MeshVTKLoader', name='loader', filename=os.path.join(self.bank_dir, "volume"+self.angle+".vtk"), scale3d=[1.0, 1.0, 1.0] ) self.node.createObject('TetrahedronSetTopologyContainer', src="@loader", name="container") self.node.createObject('TetrahedronSetGeometryAlgorithms') self.node.createObject('MechanicalObject', template='Vec3d', name='dofs', showIndices='false', showIndicesScale='0.001', rx='0') self.node.createObject('UniformMass', totalMass=str(self.mass)) # self.node.createObject('MeshMatrixMass', totalMass=str(self.mass)) self.node.createObject('TetrahedronFEMForceField', template='Vec3d', method='large', name='FEM', drawAsEdges="1", poissonRatio=str(self.poissonRatio), youngModulus=str(self.body_ym)) self.node.createObject('BoxROI', name='membraneROISubTopo', box='-300 300 -0.1 300 -300 0.1', computeTetrahedra="false", drawBoxes='true') self.node.createObject('GenericConstraintCorrection', solverName="preconditioner") # Paper layer self.paper_node = self.node.createChild('paperNode') self.paper_node.createObject( 'TriangleSetTopologyContainer', position='@../membraneROISubTopo.pointsInROI', triangles='@../membraneROISubTopo.trianglesInROI', name='container') self.paper_node.createObject( 'TriangleFEMForceField', template='Vec3d', name='FEM', method='large', poissonRatio=str(self.paperPoissonRatio), youngModulus=str(self.paper_ym) ) # Cavity and pressure constraint self.cavity_node = self.node.createChild('cavityNode') self.cavity_node.createObject( 'MeshSTLLoader', name='loader', filename=os.path.join(self.bank_dir, 'cavity_0_0_0_' + self.angle + '.stl')) self.cavity_node.createObject('Mesh', src='@loader', name='topo') self.cavity_node.createObject('MechanicalObject', name='cavity') # this pressure constraint is how the cavity is actually controlled self.cavity_node.createObject('SurfacePressureConstraint', name="pressure_constraint", template='Vec3d', value="0.00", triangles='@topo.triangles', drawPressure='0', drawScale='0.002', valueType="pressure") self.cavity_node.createObject('BarycentricMapping', name='mapping', mapForces='false', mapMasses='false') # Collision Model self.collision_node = self.node.createChild('collisionNode') self.collision_node.createObject( 'MeshSTLLoader', name='loader', filename=os.path.join(self.bank_dir, "volume_collision_"+self.angle+".stl")) self.collision_node.createObject('TriangleSetTopologyContainer', src='@loader', name='container') self.collision_node.createObject('MechanicalObject', name='collisMO', template='Vec3d') self.collision_node.createObject('TriangleCollisionModel', group="0", contactStiffness="10.0", contactFriction=self.friction_coef) self.collision_node.createObject('LineCollisionModel', group="0", contactStiffness="10.0", contactFriction=str(self.friction_coef)) self.collision_node.createObject('PointCollisionModel', group="0", contactStiffness="10.0", contactFriction=str(self.friction_coef)) self.collision_node.createObject('BarycentricMapping') # Visual Model self.visual_node = self.node.createChild('visualNode') self.visual_node.createObject( 'MeshVTKLoader', name='loader', filename=os.path.join(self.bank_dir, "volume"+self.angle+".vtk"), scale3d=[1.0, 1.0, 1.0] ) self.visual_node.createObject('OglModel', src="@loader", color='0.7 0.7 0.7 0.6') self.visual_node.createObject("BarycentricMapping") class DiskWithLegs(): volume_mesh = './meshes/disk_meshes/disk.vtk' collision_mesh = './meshes/disk_meshes/collision.stl' poissonRatio = 0.05 youngModulus = 96626 mass = 0.0 friction_coef = 0.7 def __init__(self, leg_angles): self.leg_angles = leg_angles def act(self, pressures): for leg, pressure in zip(self.legs, pressures): leg.act(pressure) def load(self, root): self.node = root.createChild("diskWithLegsNode") self.create_disk(self.node) # create legs self.legs = [Pneunet(angle) for angle in self.leg_angles] for leg in self.legs: leg.load(self.node) self.create_constraints() def create_disk(self, root): self.disk_node = root.createChild("diskNode") self.disk_node.createObject('EulerImplicitSolver', name='odesolver', firstOrder="false", rayleighStiffness='0.1', rayleighMass='0.1') self.disk_node.createObject('SparseLDLSolver', name="preconditioner", template='CompressedRowSparseMatrix3d') self.disk_node.createObject( 'MeshVTKLoader', name='loader', filename=self.volume_mesh, scale3d=[1.0, 1.0, 1.0] ) self.disk_node.createObject('TetrahedronSetTopologyContainer', src="@loader", name="container") self.disk_node.createObject('MechanicalObject', template='Vec3d', name='dofs', showIndices='false', showIndicesScale='0.001', rx='0') self.disk_node.createObject('UniformMass', totalMass=self.mass) self.disk_node.createObject('TetrahedronFEMForceField', template='Vec3d', method='large', name='FEM', drawAsEdges="1", poissonRatio=self.poissonRatio, youngModulus=self.youngModulus) self.disk_node.createObject('GenericConstraintCorrection', solverName="preconditioner") # Visual Model self.visual_node = self.disk_node.createChild('visualNode') self.visual_node.createObject( 'MeshSTLLoader', name='loader', filename=self.collision_mesh, ) self.visual_node.createObject('OglModel', src="@loader", color='0.7 0.7 1 0.6') self.visual_node.createObject("BarycentricMapping") # Collision Model self.collision_node = self.disk_node.createChild('collisionNode') self.collision_node.createObject( 'MeshSTLLoader', name='loader', filename=self.collision_mesh, ) self.collision_node.createObject('TriangleSetTopologyContainer', src='@loader', name='container') self.collision_node.createObject('MechanicalObject', name='collisMO', template='Vec3d') # everything in the same collision group "0" will not contact eachother -- and self collision is not # enabled unless you turn it on -- (a sofa plugin might be needed -- not entirely sure) I think self.collision_node.createObject('TriangleCollisionModel', group="0", contactStiffness="10.0", contactFriction=self.friction_coef) self.collision_node.createObject('LineCollisionModel', group="0", contactStiffness="10.0", contactFriction=self.friction_coef) self.collision_node.createObject('PointCollisionModel', group="0", contactStiffness="10.0", contactFriction=self.friction_coef) self.collision_node.createObject('BarycentricMapping') def create_constraints(self): self.constraint_nodes = [] for leg in self.legs: self.attach_leg(leg) def attach_leg(self, leg): node = self.disk_node.createChild('leg{}ConstraintNode'.format(leg.angle)) self.constraint_nodes.append(node) # these four indices are on the four corners of one end of the leg constraint_indices = [0, 12, 1, 11] x = np.array(leg.node.loader.getData('position').value) constraint_positions = x[constraint_indices].flatten() str_constraint_pos = " ".join([str(pos) for pos in constraint_positions]) node.createObject("MechanicalObject", name="points", template="Vec3d", position=str_constraint_pos, showIndices='0') node.createObject("BarycentricMapping") for i, ind in enumerate(constraint_indices): node.createObject( "BilateralInteractionConstraint", name="leg"+leg.angle+"_"+str(ind), template="Vec3d", object1='@' + leg.node.dofs.getPathName(), object2='@' + node.points.getPathName(), first_point=str(ind), second_point=i, )
scene.py
from __future__ import print_function from stlib.physics.rigid import Floor class Scene(): """Create floor and generic solvers.""" def __init__(self, root, dt=0.01, gravity=-9800, friction_coef=0.7): self.root = root self.dt = dt self.gravity = [0, 0, gravity] self.friction_coef = friction_coef self.init_scene() def init_scene(self): required_plugins = ['SoftRobots', 'SofaPython', 'SofaMiscCollision', 'SofaSparseSolver', 'SofaOpenglVisual'] for i in required_plugins: self.root.createObject("RequiredPlugin", name='req_p' + i, pluginName=i) self.root.findData('gravity').value = self.gravity self.root.findData('dt').value = self.dt # create all the material and cavities self.root.createObject('FreeMotionAnimationLoop') self.root.createObject('GenericConstraintSolver', printLog='0', tolerance="1e-3", maxIterations="250") self.root.createObject('DefaultPipeline', name='collisionPipeline', verbose="0") self.root.createObject('BruteForceDetection', name="N2") self.root.createObject('CollisionResponse', response="FrictionContact", responseParams="mu="+str(self.friction_coef)) self.root.createObject('LocalMinDistance', name="Proximity", alarmDistance="10.5", contactDistance="0.5", angleCone="0.01") self.root.createObject( 'DefaultContactManager', response="FrictionContact", responseParams="mu="+str(self.friction_coef) ) self.root.createObject('BackgroundSetting', color='0 0.168627 0.211765') self.root.createObject('OglSceneFrame', style="Arrows", alignment="TopRight") Floor(self.root, name="Plane", translation="0 -0 -0", rotation=[90, 0, 0], color=[1.0, 0.0, 0.0], isAStaticObject=True, uniformScale=10)
23 August 2021 at 18:32 #20211HugoKeymasterHi @asedal
Since we already chatted about it in private Audrey, I let you update the post whenever it’s the right time 😉
Best,
Hugo
23 August 2021 at 18:40 #20214AudreyModeratorAll set; I added an update to the main post.
24 August 2021 at 08:33 #2022217 September 2021 at 11:46 #20369HugoKeymasterHi @sedal,
I just update this post.
Regarding the issue with the SurfacePressureConstraint detailed in the associated GitHub issue.
Note that the research team is also investigating convergence issues with such constraints. I will update you, it could also explain the difficulty to converge with your high-stiffnesses.
Best wishes,
Hugo
-
AuthorPosts
- You must be logged in to reply to this topic.