simulation-closed-kinematic-chains.py
Go to the documentation of this file.
1 import pinocchio as pin
2 import numpy as np
3 import hppfcl as fcl
4 
5 from pinocchio.visualize import MeshcatVisualizer
6 # Perform the simulation of a four-bar linkages mechanism
7 
8 height = 0.1
9 width = 0.01
10 radius = 0.05
11 
12 mass_link_A = 10.0
13 length_link_A = 1.0
14 shape_link_A = fcl.Capsule(radius, length_link_A)
15 
16 mass_link_B = 5.0
17 length_link_B = 0.6
18 shape_link_B = fcl.Capsule(radius, length_link_B)
19 
20 inertia_link_A = pin.Inertia.FromBox(mass_link_A, length_link_A, width, height)
21 placement_center_link_A = pin.SE3.Identity()
22 placement_center_link_A.translation = pin.XAxis * length_link_A / 2.0
23 placement_shape_A = placement_center_link_A.copy()
24 placement_shape_A.rotation = pin.Quaternion.FromTwoVectors(
25  pin.ZAxis, pin.XAxis
26 ).matrix()
27 
28 inertia_link_B = pin.Inertia.FromBox(mass_link_B, length_link_B, width, height)
29 placement_center_link_B = pin.SE3.Identity()
30 placement_center_link_B.translation = pin.XAxis * length_link_B / 2.0
31 placement_shape_B = placement_center_link_B.copy()
32 placement_shape_B.rotation = pin.Quaternion.FromTwoVectors(
33  pin.ZAxis, pin.XAxis
34 ).matrix()
35 
36 model = pin.Model()
37 collision_model = pin.GeometryModel()
38 
39 RED_COLOR = np.array([1.0, 0.0, 0.0, 1.0])
40 WHITE_COLOR = np.array([1.0, 1.0, 1.0, 1.0])
41 
42 base_joint_id = 0
43 geom_obj0 = pin.GeometryObject(
44  "link_A1",
45  base_joint_id,
46  pin.SE3(
47  pin.Quaternion.FromTwoVectors(pin.ZAxis, pin.XAxis).matrix(), np.zeros((3))
48  ),
49  shape_link_A,
50 )
51 geom_obj0.meshColor = WHITE_COLOR
52 collision_model.addGeometryObject(geom_obj0)
53 
54 joint1_placement = pin.SE3.Identity()
55 joint1_placement.translation = pin.XAxis * length_link_A / 2.0
56 joint1_id = model.addJoint(
57  base_joint_id, pin.JointModelRY(), joint1_placement, "link_B1"
58 )
59 model.appendBodyToJoint(joint1_id, inertia_link_B, placement_center_link_B)
60 geom_obj1 = pin.GeometryObject("link_B1", joint1_id, placement_shape_B, shape_link_B)
61 geom_obj1.meshColor = RED_COLOR
62 collision_model.addGeometryObject(geom_obj1)
63 
64 joint2_placement = pin.SE3.Identity()
65 joint2_placement.translation = pin.XAxis * length_link_B
66 joint2_id = model.addJoint(joint1_id, pin.JointModelRY(), joint2_placement, "link_A2")
67 model.appendBodyToJoint(joint2_id, inertia_link_A, placement_center_link_A)
68 geom_obj2 = pin.GeometryObject("link_A2", joint2_id, placement_shape_A, shape_link_A)
69 geom_obj2.meshColor = WHITE_COLOR
70 collision_model.addGeometryObject(geom_obj2)
71 
72 joint3_placement = pin.SE3.Identity()
73 joint3_placement.translation = pin.XAxis * length_link_A
74 joint3_id = model.addJoint(joint2_id, pin.JointModelRY(), joint3_placement, "link_B2")
75 model.appendBodyToJoint(joint3_id, inertia_link_B, placement_center_link_B)
76 geom_obj3 = pin.GeometryObject("link_B2", joint3_id, placement_shape_B, shape_link_B)
77 geom_obj3.meshColor = RED_COLOR
78 collision_model.addGeometryObject(geom_obj3)
79 
80 visual_model = collision_model
81 viz = MeshcatVisualizer(model, collision_model, visual_model)
82 viz.initViewer(open=True)
83 viz.loadViewerModel()
84 
85 q0 = pin.neutral(model)
86 viz.display(q0)
87 
88 data = model.createData()
89 pin.forwardKinematics(model, data, q0)
90 
91 # Set the contact constraints
92 constraint1_joint1_placement = pin.SE3.Identity()
93 constraint1_joint1_placement.translation = pin.XAxis * length_link_B
94 
95 constraint1_joint2_placement = pin.SE3.Identity()
96 constraint1_joint2_placement.translation = -pin.XAxis * length_link_A / 2.0
97 
98 constraint_model = pin.RigidConstraintModel(
99  pin.ContactType.CONTACT_3D,
100  model,
101  joint3_id,
102  constraint1_joint1_placement,
103  base_joint_id,
104  constraint1_joint2_placement,
105 )
106 constraint_data = constraint_model.createData()
107 constraint_dim = constraint_model.size()
108 
109 # First, do an inverse geometry
110 rho = 1e-10
111 mu = 1e-4
112 
113 q = q0.copy()
114 
115 y = np.ones((constraint_dim))
116 data.M = np.eye(model.nv) * rho
117 kkt_constraint = pin.ContactCholeskyDecomposition(model, [constraint_model])
118 eps = 1e-10
119 N = 100
120 for k in range(N):
121  pin.computeJointJacobians(model, data, q)
122  kkt_constraint.compute(model, data, [constraint_model], [constraint_data], mu)
123  constraint_value = constraint_data.c1Mc2.translation
124 
125  J = pin.getFrameJacobian(
126  model,
127  data,
128  constraint_model.joint1_id,
129  constraint_model.joint1_placement,
130  constraint_model.reference_frame,
131  )[:3, :]
132  primal_feas = np.linalg.norm(constraint_value, np.inf)
133  dual_feas = np.linalg.norm(J.T.dot(constraint_value + y), np.inf)
134  if primal_feas < eps and dual_feas < eps:
135  print("Convergence achieved")
136  break
137  print("constraint_value:", np.linalg.norm(constraint_value))
138  rhs = np.concatenate([-constraint_value - y * mu, np.zeros(model.nv)])
139 
140  dz = kkt_constraint.solve(rhs)
141  dy = dz[:constraint_dim]
142  dq = dz[constraint_dim:]
143 
144  alpha = 1.0
145  q = pin.integrate(model, q, -alpha * dq)
146  y -= alpha * (-dy + y)
147 
148 q_sol = (q[:] + np.pi) % np.pi - np.pi
149 viz.display(q_sol)
150 
151 # Perform the simulation
152 q = q_sol.copy()
153 v = np.zeros((model.nv))
154 tau = np.zeros((model.nv))
155 dt = 5e-3
156 
157 T_sim = 100000
158 t = 0
159 mu_sim = 1e-10
160 constraint_model.corrector.Kp[:] = 10
161 constraint_model.corrector.Kd = 2.0 * np.sqrt(constraint_model.corrector.Kp)
162 pin.initConstraintDynamics(model, data, [constraint_model])
163 prox_settings = pin.ProximalSettings(1e-8, mu_sim, 10)
164 import time
165 
166 while t <= T_sim:
167  a = pin.constraintDynamics(
168  model, data, q, v, tau, [constraint_model], [constraint_data], prox_settings
169  )
170  v += a * dt
171  q = pin.integrate(model, q, v * dt)
172  viz.display(q)
173  time.sleep(dt)
174  t += dt
pinocchio.visualize
Definition: bindings/python/pinocchio/visualize/__init__.py:1
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer
Definition: meshcat_visualizer.py:532


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:50