5 import pinocchio
as pin
16 shape_link_A = fcl.Capsule(radius, length_link_A)
20 shape_link_B = fcl.Capsule(radius, length_link_B)
22 inertia_link_A = pin.Inertia.FromBox(mass_link_A, length_link_A, width, height)
23 placement_center_link_A = pin.SE3.Identity()
24 placement_center_link_A.translation = pin.XAxis * length_link_A / 2.0
25 placement_shape_A = placement_center_link_A.copy()
26 placement_shape_A.rotation = pin.Quaternion.FromTwoVectors(
30 inertia_link_B = pin.Inertia.FromBox(mass_link_B, length_link_B, width, height)
31 placement_center_link_B = pin.SE3.Identity()
32 placement_center_link_B.translation = pin.XAxis * length_link_B / 2.0
33 placement_shape_B = placement_center_link_B.copy()
34 placement_shape_B.rotation = pin.Quaternion.FromTwoVectors(
39 collision_model = pin.GeometryModel()
41 RED_COLOR = np.array([1.0, 0.0, 0.0, 1.0])
42 WHITE_COLOR = np.array([1.0, 1.0, 1.0, 1.0])
45 geom_obj0 = pin.GeometryObject(
48 pin.SE3(pin.Quaternion.FromTwoVectors(pin.ZAxis, pin.XAxis).matrix(), np.zeros(3)),
51 geom_obj0.meshColor = WHITE_COLOR
52 collision_model.addGeometryObject(geom_obj0)
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"
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)
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)
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)
80 visual_model = collision_model
82 viz.initViewer(open=
True)
85 q0 = pin.neutral(model)
88 data = model.createData()
89 pin.forwardKinematics(model, data, q0)
92 constraint1_joint1_placement = pin.SE3.Identity()
93 constraint1_joint1_placement.translation = pin.XAxis * length_link_B
95 constraint1_joint2_placement = pin.SE3.Identity()
96 constraint1_joint2_placement.translation = -pin.XAxis * length_link_A / 2.0
98 constraint_model = pin.RigidConstraintModel(
99 pin.ContactType.CONTACT_3D,
102 constraint1_joint1_placement,
104 constraint1_joint2_placement,
106 constraint_data = constraint_model.createData()
107 constraint_dim = constraint_model.size()
115 y = np.ones(constraint_dim)
116 data.M = np.eye(model.nv) * rho
117 kkt_constraint = pin.ContactCholeskyDecomposition(model, [constraint_model])
121 pin.computeJointJacobians(model, data, q)
122 kkt_constraint.compute(model, data, [constraint_model], [constraint_data], mu)
123 constraint_value = constraint_data.c1Mc2.translation
125 J = pin.getFrameJacobian(
128 constraint_model.joint1_id,
129 constraint_model.joint1_placement,
130 constraint_model.reference_frame,
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")
137 print(
"constraint_value:", np.linalg.norm(constraint_value))
138 rhs = np.concatenate([-constraint_value - y * mu, np.zeros(model.nv)])
140 dz = kkt_constraint.solve(rhs)
141 dy = dz[:constraint_dim]
142 dq = dz[constraint_dim:]
145 q = pin.integrate(model, q, -alpha * dq)
146 y -= alpha * (-dy + y)
148 q_sol = (q[:] + np.pi) % np.pi - np.pi
153 v = np.zeros(model.nv)
154 tau = np.zeros(model.nv)
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)
166 a = pin.constraintDynamics(
167 model, data, q, v, tau, [constraint_model], [constraint_data], prox_settings
170 q = pin.integrate(model, q, v * dt)