3 import example_robot_data
8 robot = example_robot_data.load(
"talos")
12 state_name =
"half_sitting"
14 robot.q0 = robot.model.referenceConfigurations[state_name]
18 lfFoot, rfFoot, lhFoot, rhFoot = (
21 "gripper_left_fingertip_3_link",
22 "gripper_right_fingertip_3_link",
25 foot_frames = [lfFoot, rfFoot, lhFoot, rhFoot]
26 foot_frame_ids = [robot.model.getFrameId(frame_name)
for frame_name
in foot_frames]
28 robot.model.frames[robot.model.getFrameId(frame_name)].parent
29 for frame_name
in foot_frames
34 constraint_models = []
36 for j, frame_id
in enumerate(foot_frame_ids):
38 pinocchio.ContactType.CONTACT_6D,
41 robot.model.frames[frame_id].placement,
45 constraint_models.extend([contact_model_lf1])
50 np.array([0.6, -0.40, 1.0]),
59 robot.loadViewerModel(
"pinocchio")
60 gui = robot.viewer.gui
61 robot.display(robot.q0)
62 window_id = robot.viewer.gui.getWindowID(
"python-pinocchio")
64 robot.viewer.gui.setBackgroundColor1(window_id, [1.0, 1.0, 1.0, 1.0])
65 robot.viewer.gui.setBackgroundColor2(window_id, [1.0, 1.0, 1.0, 1.0])
66 robot.viewer.gui.addFloor(
"hpp-gui/floor")
68 robot.viewer.gui.setScale(
"hpp-gui/floor", [0.5, 0.5, 0.5])
69 robot.viewer.gui.setColor(
"hpp-gui/floor", [0.7, 0.7, 0.7, 1.0])
70 robot.viewer.gui.setLightingMode(
"hpp-gui/floor",
"OFF")
72 robot.display(robot.q0)
74 constraint_datas = [cm.createData()
for cm
in constraint_models]
80 constraint_dim = sum([cm.size()
for cm
in constraint_models])
95 y = np.ones(constraint_dim)
102 com_base = data.com[0].
copy()
107 return com_base - np.array(
111 np.abs(com_drop_amp * np.sin(2.0 * np.pi * k * speed / (N_full))),
119 com_act = data.com[0].
copy()
121 kkt_constraint.compute(model, data, constraint_models, constraint_datas, mu)
122 constraint_value = np.concatenate(
128 model, data, cm.joint1_id, cm.joint1_placement, cm.reference_frame
130 for cm
in constraint_models
133 primal_feas = np.linalg.norm(constraint_value, np.inf)
134 print(J.shape, constraint_value.shape, y.shape)
135 dual_feas = np.linalg.norm(J.T.dot(constraint_value + y), np.inf)
136 print(
"primal_feas:", primal_feas)
137 print(
"dual_feas:", dual_feas)
141 print(
"constraint_value:", np.linalg.norm(constraint_value))
142 print(
"com_error:", np.linalg.norm(com_err))
143 rhs = np.concatenate(
144 [-constraint_value - y * mu, kp * mass * com_err, np.zeros(model.nv - 3)]
146 dz = kkt_constraint.solve(rhs)
147 dy = dz[:constraint_dim]
148 dq = dz[constraint_dim:]
151 y -= alpha * (-dy + y)