6 import pinocchio
as pin
11 """Standard TSID formulation for a biped robot standing on its rectangular feet. 14 - 6d rigid contact constraint for both feet 15 - Regularization task for contact forces 18 def __init__(self, conf, viewer=pin.visualize.MeshcatVisualizer):
21 conf.urdf, [conf.path], pin.JointModelFreeFlyer(),
False 25 pin.loadReferenceConfigurations(self.
model, conf.srdf,
False)
26 self.
q0 = q = self.
model.referenceConfigurations[
"half_sitting"]
27 v = np.zeros(robot.nv)
29 assert self.
model.existFrame(conf.rf_frame_name)
30 assert self.
model.existFrame(conf.lf_frame_name)
33 formulation.computeProblemData(0.0, q, v)
34 data = formulation.data()
35 contact_Point = np.ones((3, 4)) * (-conf.lz)
36 contact_Point[0, :] = [-conf.lxn, -conf.lxn, conf.lxp, conf.lxp]
37 contact_Point[1, :] = [-conf.lyn, conf.lyp, -conf.lyn, conf.lyp]
39 contactRF = tsid.Contact6d(
49 contactRF.setKp(conf.kp_contact * np.ones(6))
50 contactRF.setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(6))
51 self.
RF = robot.model().getFrameId(conf.rf_frame_name)
52 H_rf_ref = robot.framePosition(data, self.
RF)
55 q[2] -= H_rf_ref.translation[2] - conf.lz
56 formulation.computeProblemData(0.0, q, v)
57 data = formulation.data()
58 H_rf_ref = robot.framePosition(data, self.
RF)
59 contactRF.setReference(H_rf_ref)
60 if conf.w_contact >= 0.0:
61 formulation.addRigidContact(contactRF, conf.w_forceRef, conf.w_contact, 1)
63 formulation.addRigidContact(contactRF, conf.w_forceRef)
65 contactLF = tsid.Contact6d(
75 contactLF.setKp(conf.kp_contact * np.ones(6))
76 contactLF.setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(6))
77 self.
LF = robot.model().getFrameId(conf.lf_frame_name)
78 H_lf_ref = robot.framePosition(data, self.
LF)
79 contactLF.setReference(H_lf_ref)
80 if conf.w_contact >= 0.0:
81 formulation.addRigidContact(contactLF, conf.w_forceRef, conf.w_contact, 1)
83 formulation.addRigidContact(contactLF, conf.w_forceRef)
85 comTask = tsid.TaskComEquality(
"task-com", robot)
86 comTask.setKp(conf.kp_com * np.ones(3))
87 comTask.setKd(2.0 * np.sqrt(conf.kp_com) * np.ones(3))
88 formulation.addMotionTask(comTask, conf.w_com, 1, 0.0)
90 copTask = tsid.TaskCopEquality(
"task-cop", robot)
91 formulation.addForceTask(copTask, conf.w_cop, 1, 0.0)
93 amTask = tsid.TaskAMEquality(
"task-am", robot)
94 amTask.setKp(conf.kp_am * np.array([1.0, 1.0, 0.0]))
95 amTask.setKd(2.0 * np.sqrt(conf.kp_am * np.array([1.0, 1.0, 0.0])))
96 formulation.addMotionTask(amTask, conf.w_am, 1, 0.0)
97 sampleAM = tsid.TrajectorySample(3)
98 amTask.setReference(sampleAM)
100 postureTask = tsid.TaskJointPosture(
"task-posture", robot)
101 postureTask.setKp(conf.kp_posture * conf.gain_vector)
102 postureTask.setKd(2.0 * np.sqrt(conf.kp_posture * conf.gain_vector))
103 postureTask.setMask(conf.masks_posture)
104 formulation.addMotionTask(postureTask, conf.w_posture, 1, 0.0)
107 "task-left-foot", self.
robot, self.
conf.lf_frame_name
111 self.
trajLF = tsid.TrajectorySE3Constant(
"traj-left-foot", H_lf_ref)
115 "task-right-foot", self.
robot, self.
conf.rf_frame_name
119 self.
trajRF = tsid.TrajectorySE3Constant(
"traj-right-foot", H_rf_ref)
122 self.
tau_max = conf.tau_max_scaling * robot.model().effortLimit[-robot.na :]
124 actuationBoundsTask = tsid.TaskActuationBounds(
"task-actuation-bounds", robot)
126 if conf.w_torque_bounds > 0.0:
127 formulation.addActuationTask(
128 actuationBoundsTask, conf.w_torque_bounds, 0, 0.0
131 jointBoundsTask = tsid.TaskJointBounds(
"task-joint-bounds", robot, conf.dt)
132 self.
v_max = conf.v_max_scaling * robot.model().velocityLimit[-robot.na :]
134 jointBoundsTask.setVelocityBounds(self.
v_min, self.
v_max)
135 if conf.w_joint_bounds > 0.0:
136 formulation.addMotionTask(jointBoundsTask, conf.w_joint_bounds, 0, 0.0)
138 com_ref = robot.com(data)
139 self.
trajCom = tsid.TrajectoryEuclidianConstant(
"traj_com", com_ref)
143 self.
trajPosture = tsid.TrajectoryEuclidianConstant(
"traj_joint", q_ref)
144 postureTask.setReference(self.
trajPosture.computeNext())
156 self.
solver = tsid.SolverHQuadProgFast(
"qp solver")
157 self.
solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)
176 conf.urdf, [conf.path], pin.JointModelFreeFlyer()
178 if viewer == pin.visualize.GepettoVisualizer:
179 import gepetto.corbaserver
181 launched = subprocess.getstatusoutput(
182 "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l" 184 if int(launched[1]) == 0:
185 os.system(
"gepetto-gui &")
192 self.
viz.initViewer(loadModel=
True)
193 self.
viz.displayCollisions(
False)
194 self.
viz.displayVisuals(
True)
199 self.
gui.addFloor(
"world/floor")
200 self.
gui.setLightingMode(
"world/floor",
"OFF")
201 elif viewer == pin.visualize.MeshcatVisualizer:
207 self.
viz.initViewer(loadModel=
True, open=
True)
211 if hasattr(self,
"viz"):
215 v_mean = v + 0.5 * dt * dv
217 q = pin.integrate(self.
model, q, dt * v_mean)
252 H = self.
robot.framePosition(data, self.
LF)
253 v = self.
robot.frameVelocity(data, self.
LF)
255 return H.translation, v.linear, a[:3]
259 H = self.
robot.framePosition(data, self.
RF)
260 v = self.
robot.frameVelocity(data, self.
RF)
262 return H.translation, v.linear, a[:3]
266 self.
trajRF.setReference(H_rf_ref)
274 self.
trajLF.setReference(H_lf_ref)
283 if self.
conf.w_contact >= 0.0:
295 if self.
conf.w_contact >= 0.0:
def get_LF_3d_pos_vel_acc(self, dv)
def __init__(self, conf, viewer=pin.visualize.MeshcatVisualizer)
def get_RF_3d_pos_vel_acc(self, dv)
def set_LF_3d_ref(self, pos, vel, acc)
def add_contact_LF(self, transition_time=0.0)
def get_placement_RF(self)
def remove_contact_RF(self, transition_time=0.0)
def integrate_dv(self, q, v, dv, dt)
def add_contact_RF(self, transition_time=0.0)
def get_placement_LF(self)
def set_RF_3d_ref(self, pos, vel, acc)
def remove_contact_LF(self, transition_time=0.0)
def set_com_ref(self, pos, vel, acc)