3 import example_robot_data
8 robot = example_robot_data.load(
"cassie")
10 constraint_models = robot.constraint_models
16 foot_joints = [
"left-plantar-foot-joint",
"right-plantar-foot-joint"]
17 foot_joint_ids = [robot.model.getJointId(joint_name)
for joint_name
in foot_joints]
19 front_placement =
pinocchio.SE3(np.identity(3), np.array([-0.1, 0.11, 0.0]))
21 back_placement =
pinocchio.SE3(np.identity(3), np.array([0.03, -0.0, 0.0]))
23 foot_length = np.linalg.norm(front_placement.translation - back_placement.translation)
28 mid_point = np.zeros(3)
30 for joint_id
in foot_joint_ids:
31 joint2_placement = robot.data.oMi[joint_id] * front_placement
32 joint2_placement.translation[2] = 0
34 pinocchio.ContactType.CONTACT_3D,
40 pinocchio.ReferenceFrame.LOCAL,
43 mid_point += joint2_placement.translation
44 joint2_placement.translation[0] -= foot_length
47 pinocchio.ContactType.CONTACT_3D,
53 pinocchio.ReferenceFrame.LOCAL,
56 mid_point += joint2_placement.translation
57 constraint_models.extend([contact_model_lf1, contact_model_lf2])
64 robot.loadViewerModel(
"pinocchio")
65 gui = robot.viewer.gui
66 robot.display(robot.q0)
68 constraint_datas = pinocchio.StdVec_RigidConstraintData()
69 for cm
in constraint_models:
70 constraint_datas.append(cm.createData())
75 for j, cm
in enumerate(robot.constraint_models):
76 pos1 = robot.data.oMi[cm.joint1_id] * cm.joint1_placement
77 pos2 = robot.data.oMi[cm.joint2_id] * cm.joint2_placement
78 name1 =
"hpp-gui/cm1_" + str(j)
79 name2 =
"hpp-gui/cm2_" + str(j)
80 gui.applyConfiguration(name1, list(pinocchio.SE3ToXYZQUAT(pos1)))
81 gui.applyConfiguration(name2, list(pinocchio.SE3ToXYZQUAT(pos2)))
86 for k
in range(model.joints[nj].nv):
87 for res
in range(200):
89 theta = res * 2.0 * np.pi / 200.0
90 v = np.zeros(robot.model.nv)
91 v[robot.model.idx_vs[nj] + k] = theta
102 constraint_dim = sum([cm.size()
for cm
in constraint_models])
109 window_id = robot.viewer.gui.getWindowID(
"python-pinocchio")
110 robot.viewer.gui.setBackgroundColor1(window_id, [1.0, 1.0, 1.0, 1.0])
111 robot.viewer.gui.setBackgroundColor2(window_id, [1.0, 1.0, 1.0, 1.0])
112 robot.viewer.gui.addFloor(
"hpp-gui/floor")
113 robot.viewer.gui.setScale(
"hpp-gui/floor", [0.5, 0.5, 0.5])
114 robot.viewer.gui.setColor(
"hpp-gui/floor", [0.7, 0.7, 0.7, 1.0])
115 robot.viewer.gui.setLightingMode(
"hpp-gui/floor",
"OFF")
122 for j, cm
in enumerate(constraint_models):
123 pos1 = robot.data.oMi[cm.joint1_id] * cm.joint1_placement
124 pos2 = robot.data.oMi[cm.joint2_id] * cm.joint2_placement
125 name1 =
"hpp-gui/cm1_" + str(j)
126 name2 =
"hpp-gui/cm2_" + str(j)
127 red_color = 1.0 * float(j) / float(len(constraint_models))
129 robot.viewer.gui.addXYZaxis(
130 name1, [red_color, 1.0, 1.0 - red_color, transparency], radius, axis_size
132 robot.viewer.gui.addXYZaxis(
133 name2, [red_color, 1.0, 1.0 - red_color, transparency], radius, axis_size
136 gui.applyConfiguration(name1, list(pinocchio.SE3ToXYZQUAT(pos1)))
137 gui.applyConfiguration(name2, list(pinocchio.SE3ToXYZQUAT(pos2)))
139 gui.setVisibility(name1,
"OFF")
140 gui.setVisibility(name2,
"OFF")
143 mid_point_name =
"hpp-gui/mid_point"
145 robot.viewer.gui.addXYZaxis(
146 mid_point_name, [0.0, 0.0, 1.0, transparency], radius, axis_size
150 gui.applyConfiguration(mid_point_name, list(pinocchio.SE3ToXYZQUAT(mid_point_pos)))
151 gui.setVisibility(mid_point_name,
"ALWAYS_ON_TOP")
157 mass = robot.data.mass[0]
159 com_base = robot.data.com[0].
copy()
160 com_base[:2] = mid_point[:2]
165 return com_base - np.array([0.0, 0.0, np.abs(com_drop_amp)])
168 def squashing(model, data, q_in, Nin=N, epsin=eps, verbose=True):
170 y = np.ones(constraint_dim)
176 kp = np.array([1.0, 1.0, 0.1])
181 com_act = robot.data.com[0].
copy()
183 kkt_constraint.compute(
184 robot.model, robot.data, constraint_models, constraint_datas, mu
186 constraint_value1 = np.concatenate(
187 [pinocchio.log(cd.c1Mc2)
for cd
in constraint_datas[:-4]]
189 constraint_value2 = np.concatenate(
190 [cd.c1Mc2.translation
for cd
in constraint_datas[-4:]]
192 constraint_value = np.concatenate([constraint_value1, constraint_value2])
203 for cm
in constraint_models[:-4]
215 for cm
in constraint_models[-4:]
218 J = np.vstack([J1, J2])
219 primal_feas = np.linalg.norm(constraint_value, np.inf)
221 dual_feas = np.linalg.norm(J.T.dot(constraint_value + y), np.inf)
222 if primal_feas < epsin
and dual_feas < epsin:
223 print(
"Convergence achieved")
226 print(
"constraint_value:", np.linalg.norm(constraint_value))
227 print(
"com_error:", np.linalg.norm(com_err))
229 print(
"com_act", com_act)
230 rhs = np.concatenate(
231 [-constraint_value - y * mu, kp * com_err, np.zeros(robot.model.nv - 3)]
233 dz = kkt_constraint.solve(rhs)
234 dy = dz[:constraint_dim]
235 dq = dz[constraint_dim:]
238 y -= alpha * (-dy + y)
241 gui.applyConfiguration(
249 qin = robot.q0.copy()
250 for k
in range(1000):
256 qout =
squashing(robot.model, data, qin, Nin=100000, epsin=1e-10, verbose=
False)