6 import pinocchio
as pin
12 """Standard TSID formulation for a biped robot standing on its rectangular feet.
15 - 6d rigid contact constraint for both feet
16 - Regularization task for contact forces
19 def __init__(self, conf, viewer=pin.visualize.MeshcatVisualizer):
22 conf.urdf, [conf.path], pin.JointModelFreeFlyer(),
False
26 pin.loadReferenceConfigurations(self.
model, conf.srdf,
False)
27 self.
q0 = q = self.
model.referenceConfigurations[
"half_sitting"]
28 v = np.zeros(robot.nv)
30 assert self.
model.existFrame(conf.rf_frame_name)
31 assert self.
model.existFrame(conf.lf_frame_name)
34 formulation.computeProblemData(0.0, q, v)
35 data = formulation.data()
36 contact_Point = np.ones((3, 4)) * (-conf.lz)
37 contact_Point[0, :] = [-conf.lxn, -conf.lxn, conf.lxp, conf.lxp]
38 contact_Point[1, :] = [-conf.lyn, conf.lyp, -conf.lyn, conf.lyp]
40 contactRF = tsid.Contact6d(
50 contactRF.setKp(conf.kp_contact * np.ones(6))
51 contactRF.setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(6))
52 self.
RF = robot.model().getFrameId(conf.rf_frame_name)
53 H_rf_ref = robot.framePosition(data, self.
RF)
56 q[2] -= H_rf_ref.translation[2] - conf.lz
57 formulation.computeProblemData(0.0, q, v)
58 data = formulation.data()
59 H_rf_ref = robot.framePosition(data, self.
RF)
60 contactRF.setReference(H_rf_ref)
61 if conf.w_contact >= 0.0:
62 formulation.addRigidContact(contactRF, conf.w_forceRef, conf.w_contact, 1)
64 formulation.addRigidContact(contactRF, conf.w_forceRef)
66 contactLF = tsid.Contact6d(
76 contactLF.setKp(conf.kp_contact * np.ones(6))
77 contactLF.setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(6))
78 self.
LF = robot.model().getFrameId(conf.lf_frame_name)
79 H_lf_ref = robot.framePosition(data, self.
LF)
80 contactLF.setReference(H_lf_ref)
81 if conf.w_contact >= 0.0:
82 formulation.addRigidContact(contactLF, conf.w_forceRef, conf.w_contact, 1)
84 formulation.addRigidContact(contactLF, conf.w_forceRef)
86 comTask = tsid.TaskComEquality(
"task-com", robot)
87 comTask.setKp(conf.kp_com * np.ones(3))
88 comTask.setKd(2.0 * np.sqrt(conf.kp_com) * np.ones(3))
89 formulation.addMotionTask(comTask, conf.w_com, 1, 0.0)
91 copTask = tsid.TaskCopEquality(
"task-cop", robot)
92 formulation.addForceTask(copTask, conf.w_cop, 1, 0.0)
94 amTask = tsid.TaskAMEquality(
"task-am", robot)
95 amTask.setKp(conf.kp_am * np.array([1.0, 1.0, 0.0]))
96 amTask.setKd(2.0 * np.sqrt(conf.kp_am * np.array([1.0, 1.0, 0.0])))
97 formulation.addMotionTask(amTask, conf.w_am, 1, 0.0)
98 sampleAM = tsid.TrajectorySample(3)
99 amTask.setReference(sampleAM)
101 postureTask = tsid.TaskJointPosture(
"task-posture", robot)
102 postureTask.setKp(conf.kp_posture * conf.gain_vector)
103 postureTask.setKd(2.0 * np.sqrt(conf.kp_posture * conf.gain_vector))
104 postureTask.setMask(conf.masks_posture)
105 formulation.addMotionTask(postureTask, conf.w_posture, 1, 0.0)
108 "task-left-foot", self.
robot, self.
conf.lf_frame_name
112 self.
trajLF = tsid.TrajectorySE3Constant(
"traj-left-foot", H_lf_ref)
116 "task-right-foot", self.
robot, self.
conf.rf_frame_name
120 self.
trajRF = tsid.TrajectorySE3Constant(
"traj-right-foot", H_rf_ref)
123 self.
tau_max = conf.tau_max_scaling * robot.model().effortLimit[-robot.na :]
125 actuationBoundsTask = tsid.TaskActuationBounds(
"task-actuation-bounds", robot)
127 if conf.w_torque_bounds > 0.0:
128 formulation.addActuationTask(
129 actuationBoundsTask, conf.w_torque_bounds, 0, 0.0
132 jointBoundsTask = tsid.TaskJointBounds(
"task-joint-bounds", robot, conf.dt)
133 self.
v_max = conf.v_max_scaling * robot.model().velocityLimit[-robot.na :]
135 jointBoundsTask.setVelocityBounds(self.
v_min, self.
v_max)
136 if conf.w_joint_bounds > 0.0:
137 formulation.addMotionTask(jointBoundsTask, conf.w_joint_bounds, 0, 0.0)
139 com_ref = robot.com(data)
140 self.
trajCom = tsid.TrajectoryEuclidianConstant(
"traj_com", com_ref)
144 self.
trajPosture = tsid.TrajectoryEuclidianConstant(
"traj_joint", q_ref)
145 postureTask.setReference(self.
trajPosture.computeNext())
157 self.
solver = tsid.SolverHQuadProgFast(
"qp solver")
158 self.
solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)
177 conf.urdf, [conf.path], pin.JointModelFreeFlyer()
179 if viewer == pin.visualize.GepettoVisualizer:
180 launched = subprocess.getstatusoutput(
181 "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l"
183 if int(launched[1]) == 0:
184 os.system(
"gepetto-gui &")
191 self.
viz.initViewer(loadModel=
True)
192 self.
viz.displayCollisions(
False)
193 self.
viz.displayVisuals(
True)
198 self.
gui.addFloor(
"world/floor")
199 self.
gui.setLightingMode(
"world/floor",
"OFF")
200 elif viewer == pin.visualize.MeshcatVisualizer:
206 self.
viz.initViewer(loadModel=
True, open=
True)
210 if hasattr(self,
"viz"):
214 v_mean = v + 0.5 * dt * dv
216 q = pin.integrate(self.
model, q, dt * v_mean)
251 H = self.
robot.framePosition(data, self.
LF)
252 v = self.
robot.frameVelocity(data, self.
LF)
254 return H.translation, v.linear, a[:3]
258 H = self.
robot.framePosition(data, self.
RF)
259 v = self.
robot.frameVelocity(data, self.
RF)
261 return H.translation, v.linear, a[:3]
265 self.
trajRF.setReference(H_rf_ref)
273 self.
trajLF.setReference(H_lf_ref)
282 if self.
conf.w_contact >= 0.0:
294 if self.
conf.w_contact >= 0.0: