tsid_biped.py
Go to the documentation of this file.
1 import os
2 import subprocess
3 import time
4 
5 import numpy as np
6 import pinocchio as pin
7 
8 import tsid
9 
10 
11 class TsidBiped:
12  """Standard TSID formulation for a biped robot standing on its rectangular feet.
13  - Center of mass task
14  - Postural task
15  - 6d rigid contact constraint for both feet
16  - Regularization task for contact forces
17  """
18 
19  def __init__(self, conf, viewer=pin.visualize.MeshcatVisualizer):
20  self.conf = conf
21  self.robot = tsid.RobotWrapper(
22  conf.urdf, [conf.path], pin.JointModelFreeFlyer(), False
23  )
24  robot = self.robot
25  self.model = robot.model()
26  pin.loadReferenceConfigurations(self.model, conf.srdf, False)
27  self.q0 = q = self.model.referenceConfigurations["half_sitting"]
28  v = np.zeros(robot.nv)
29 
30  assert self.model.existFrame(conf.rf_frame_name)
31  assert self.model.existFrame(conf.lf_frame_name)
32 
33  formulation = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False)
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]
39 
40  contactRF = tsid.Contact6d(
41  "contact_rfoot",
42  robot,
43  conf.rf_frame_name,
44  contact_Point,
45  conf.contactNormal,
46  conf.mu,
47  conf.fMin,
48  conf.fMax,
49  )
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)
54 
55  # modify initial robot configuration so that foot is on the ground (z=0)
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)
63  else:
64  formulation.addRigidContact(contactRF, conf.w_forceRef)
65 
66  contactLF = tsid.Contact6d(
67  "contact_lfoot",
68  robot,
69  conf.lf_frame_name,
70  contact_Point,
71  conf.contactNormal,
72  conf.mu,
73  conf.fMin,
74  conf.fMax,
75  )
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)
83  else:
84  formulation.addRigidContact(contactLF, conf.w_forceRef)
85 
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)
90 
91  copTask = tsid.TaskCopEquality("task-cop", robot)
92  formulation.addForceTask(copTask, conf.w_cop, 1, 0.0)
93 
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)
100 
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)
106 
107  self.leftFootTask = tsid.TaskSE3Equality(
108  "task-left-foot", self.robot, self.conf.lf_frame_name
109  )
110  self.leftFootTask.setKp(self.conf.kp_foot * np.ones(6))
111  self.leftFootTask.setKd(2.0 * np.sqrt(self.conf.kp_foot) * np.ones(6))
112  self.trajLF = tsid.TrajectorySE3Constant("traj-left-foot", H_lf_ref)
113  formulation.addMotionTask(self.leftFootTask, self.conf.w_foot, 1, 0.0)
114 
115  self.rightFootTask = tsid.TaskSE3Equality(
116  "task-right-foot", self.robot, self.conf.rf_frame_name
117  )
118  self.rightFootTask.setKp(self.conf.kp_foot * np.ones(6))
119  self.rightFootTask.setKd(2.0 * np.sqrt(self.conf.kp_foot) * np.ones(6))
120  self.trajRF = tsid.TrajectorySE3Constant("traj-right-foot", H_rf_ref)
121  formulation.addMotionTask(self.rightFootTask, self.conf.w_foot, 1, 0.0)
122 
123  self.tau_max = conf.tau_max_scaling * robot.model().effortLimit[-robot.na :]
124  self.tau_min = -self.tau_max
125  actuationBoundsTask = tsid.TaskActuationBounds("task-actuation-bounds", robot)
126  actuationBoundsTask.setBounds(self.tau_min, self.tau_max)
127  if conf.w_torque_bounds > 0.0:
128  formulation.addActuationTask(
129  actuationBoundsTask, conf.w_torque_bounds, 0, 0.0
130  )
131 
132  jointBoundsTask = tsid.TaskJointBounds("task-joint-bounds", robot, conf.dt)
133  self.v_max = conf.v_max_scaling * robot.model().velocityLimit[-robot.na :]
134  self.v_min = -self.v_max
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)
138 
139  com_ref = robot.com(data)
140  self.trajCom = tsid.TrajectoryEuclidianConstant("traj_com", com_ref)
141  self.sample_com = self.trajCom.computeNext()
142 
143  q_ref = q[7:]
144  self.trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q_ref)
145  postureTask.setReference(self.trajPosture.computeNext())
146 
147  self.sampleLF = self.trajLF.computeNext()
148  self.sample_LF_pos = self.sampleLF.pos()
149  self.sample_LF_vel = self.sampleLF.vel()
150  self.sample_LF_acc = self.sampleLF.acc()
151 
152  self.sampleRF = self.trajRF.computeNext()
153  self.sample_RF_pos = self.sampleRF.pos()
154  self.sample_RF_vel = self.sampleRF.vel()
155  self.sample_RF_acc = self.sampleRF.acc()
156 
157  self.solver = tsid.SolverHQuadProgFast("qp solver")
158  self.solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)
159 
160  self.comTask = comTask
161  self.copTask = copTask
162  self.amTask = amTask
163  self.postureTask = postureTask
164  self.contactRF = contactRF
165  self.contactLF = contactLF
166  self.actuationBoundsTask = actuationBoundsTask
167  self.jointBoundsTask = jointBoundsTask
168  self.formulation = formulation
169  self.q = q
170  self.v = v
171 
172  self.contact_LF_active = True
173  self.contact_RF_active = True
174 
175  if viewer:
176  self.robot_display = pin.RobotWrapper.BuildFromURDF(
177  conf.urdf, [conf.path], pin.JointModelFreeFlyer()
178  )
179  if viewer == pin.visualize.GepettoVisualizer:
180  launched = subprocess.getstatusoutput(
181  "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l"
182  )
183  if int(launched[1]) == 0:
184  os.system("gepetto-gui &")
185  time.sleep(1)
186  self.viz = viewer(
187  self.robot_display.model,
188  self.robot_display.collision_model,
189  self.robot_display.visual_model,
190  )
191  self.viz.initViewer(loadModel=True)
192  self.viz.displayCollisions(False)
193  self.viz.displayVisuals(True)
194  self.viz.display(q)
195 
196  self.gui = self.viz.viewer.gui
197  # self.gui.setCameraTransform(0, conf.CAMERA_TRANSFORM)
198  self.gui.addFloor("world/floor")
199  self.gui.setLightingMode("world/floor", "OFF")
200  elif viewer == pin.visualize.MeshcatVisualizer:
201  self.viz = viewer(
202  self.robot_display.model,
203  self.robot_display.collision_model,
204  self.robot_display.visual_model,
205  )
206  self.viz.initViewer(loadModel=True, open=True)
207  self.viz.display(q)
208 
209  def display(self, q):
210  if hasattr(self, "viz"):
211  self.viz.display(q)
212 
213  def integrate_dv(self, q, v, dv, dt):
214  v_mean = v + 0.5 * dt * dv
215  v += dt * dv
216  q = pin.integrate(self.model, q, dt * v_mean)
217  return q, v
218 
219  def get_placement_LF(self):
220  return self.robot.framePosition(self.formulation.data(), self.LF)
221 
222  def get_placement_RF(self):
223  return self.robot.framePosition(self.formulation.data(), self.RF)
224 
225  def set_com_ref(self, pos, vel, acc):
226  self.sample_com.pos(pos)
227  self.sample_com.vel(vel)
228  self.sample_com.acc(acc)
229  self.comTask.setReference(self.sample_com)
230 
231  def set_RF_3d_ref(self, pos, vel, acc):
232  self.sample_RF_pos[:3] = pos
233  self.sample_RF_vel[:3] = vel
234  self.sample_RF_acc[:3] = acc
235  self.sampleRF.pos(self.sample_RF_pos)
236  self.sampleRF.vel(self.sample_RF_vel)
237  self.sampleRF.acc(self.sample_RF_acc)
238  self.rightFootTask.setReference(self.sampleRF)
239 
240  def set_LF_3d_ref(self, pos, vel, acc):
241  self.sample_LF_pos[:3] = pos
242  self.sample_LF_vel[:3] = vel
243  self.sample_LF_acc[:3] = acc
244  self.sampleLF.pos(self.sample_LF_pos)
245  self.sampleLF.vel(self.sample_LF_vel)
246  self.sampleLF.acc(self.sample_LF_acc)
247  self.leftFootTask.setReference(self.sampleLF)
248 
249  def get_LF_3d_pos_vel_acc(self, dv):
250  data = self.formulation.data()
251  H = self.robot.framePosition(data, self.LF)
252  v = self.robot.frameVelocity(data, self.LF)
253  a = self.leftFootTask.getAcceleration(dv)
254  return H.translation, v.linear, a[:3]
255 
256  def get_RF_3d_pos_vel_acc(self, dv):
257  data = self.formulation.data()
258  H = self.robot.framePosition(data, self.RF)
259  v = self.robot.frameVelocity(data, self.RF)
260  a = self.rightFootTask.getAcceleration(dv)
261  return H.translation, v.linear, a[:3]
262 
263  def remove_contact_RF(self, transition_time=0.0):
264  H_rf_ref = self.robot.framePosition(self.formulation.data(), self.RF)
265  self.trajRF.setReference(H_rf_ref)
266  self.rightFootTask.setReference(self.trajRF.computeNext())
267 
268  self.formulation.removeRigidContact(self.contactRF.name, transition_time)
269  self.contact_RF_active = False
270 
271  def remove_contact_LF(self, transition_time=0.0):
272  H_lf_ref = self.robot.framePosition(self.formulation.data(), self.LF)
273  self.trajLF.setReference(H_lf_ref)
274  self.leftFootTask.setReference(self.trajLF.computeNext())
275 
276  self.formulation.removeRigidContact(self.contactLF.name, transition_time)
277  self.contact_LF_active = False
278 
279  def add_contact_RF(self, transition_time=0.0):
280  H_rf_ref = self.robot.framePosition(self.formulation.data(), self.RF)
281  self.contactRF.setReference(H_rf_ref)
282  if self.conf.w_contact >= 0.0:
283  self.formulation.addRigidContact(
284  self.contactRF, self.conf.w_forceRef, self.conf.w_contact, 1
285  )
286  else:
287  self.formulation.addRigidContact(self.contactRF, self.conf.w_forceRef)
288 
289  self.contact_RF_active = True
290 
291  def add_contact_LF(self, transition_time=0.0):
292  H_lf_ref = self.robot.framePosition(self.formulation.data(), self.LF)
293  self.contactLF.setReference(H_lf_ref)
294  if self.conf.w_contact >= 0.0:
295  self.formulation.addRigidContact(
296  self.contactLF, self.conf.w_forceRef, self.conf.w_contact, 1
297  )
298  else:
299  self.formulation.addRigidContact(self.contactLF, self.conf.w_forceRef)
300 
301  self.contact_LF_active = True
tsid_biped.TsidBiped.__init__
def __init__(self, conf, viewer=pin.visualize.MeshcatVisualizer)
Definition: tsid_biped.py:19
tsid_biped.TsidBiped.leftFootTask
leftFootTask
Definition: tsid_biped.py:107
tsid_biped.TsidBiped.v_max
v_max
Definition: tsid_biped.py:133
tsid_biped.TsidBiped.q
q
Definition: tsid_biped.py:169
tsid_biped.TsidBiped.sample_LF_vel
sample_LF_vel
Definition: tsid_biped.py:149
tsid_biped.TsidBiped.sample_com
sample_com
Definition: tsid_biped.py:141
tsid_biped.TsidBiped.postureTask
postureTask
Definition: tsid_biped.py:163
tsid_biped.TsidBiped.set_RF_3d_ref
def set_RF_3d_ref(self, pos, vel, acc)
Definition: tsid_biped.py:231
tsid_biped.TsidBiped.get_RF_3d_pos_vel_acc
def get_RF_3d_pos_vel_acc(self, dv)
Definition: tsid_biped.py:256
setup.data
data
Definition: setup.in.py:48
tsid_biped.TsidBiped.trajCom
trajCom
Definition: tsid_biped.py:140
tsid_biped.TsidBiped.robot
robot
Definition: tsid_biped.py:21
tsid_biped.TsidBiped.gui
gui
Definition: tsid_biped.py:196
tsid_biped.TsidBiped.comTask
comTask
Definition: tsid_biped.py:160
tsid_biped.TsidBiped.get_placement_RF
def get_placement_RF(self)
Definition: tsid_biped.py:222
tsid_biped.TsidBiped.sample_LF_acc
sample_LF_acc
Definition: tsid_biped.py:150
tsid_biped.TsidBiped.sampleRF
sampleRF
Definition: tsid_biped.py:152
tsid_biped.TsidBiped.v
v
Definition: tsid_biped.py:170
tsid_biped.TsidBiped.sample_LF_pos
sample_LF_pos
Definition: tsid_biped.py:148
tsid_biped.TsidBiped.sample_RF_pos
sample_RF_pos
Definition: tsid_biped.py:153
tsid_biped.TsidBiped.formulation
formulation
Definition: tsid_biped.py:168
tsid_biped.TsidBiped.trajPosture
trajPosture
Definition: tsid_biped.py:144
tsid_biped.TsidBiped.model
model
Definition: tsid_biped.py:25
tsid_biped.TsidBiped.get_LF_3d_pos_vel_acc
def get_LF_3d_pos_vel_acc(self, dv)
Definition: tsid_biped.py:249
tsid_biped.TsidBiped.contactLF
contactLF
Definition: tsid_biped.py:165
tsid_biped.TsidBiped.jointBoundsTask
jointBoundsTask
Definition: tsid_biped.py:167
tsid_biped.TsidBiped.amTask
amTask
Definition: tsid_biped.py:162
tsid_biped.TsidBiped.contact_RF_active
contact_RF_active
Definition: tsid_biped.py:173
tsid_biped.TsidBiped.contact_LF_active
contact_LF_active
Definition: tsid_biped.py:172
tsid_biped.TsidBiped.integrate_dv
def integrate_dv(self, q, v, dv, dt)
Definition: tsid_biped.py:213
tsid_biped.TsidBiped.contactRF
contactRF
Definition: tsid_biped.py:164
display
tsid_biped.TsidBiped.sample_RF_vel
sample_RF_vel
Definition: tsid_biped.py:154
tsid_biped.TsidBiped.remove_contact_RF
def remove_contact_RF(self, transition_time=0.0)
Definition: tsid_biped.py:263
tsid_biped.TsidBiped.RF
RF
Definition: tsid_biped.py:52
tsid_biped.TsidBiped.tau_max
tau_max
Definition: tsid_biped.py:123
tsid_biped.TsidBiped.add_contact_LF
def add_contact_LF(self, transition_time=0.0)
Definition: tsid_biped.py:291
tsid_biped.TsidBiped.viz
viz
Definition: tsid_biped.py:186
tsid_biped.TsidBiped.sample_RF_acc
sample_RF_acc
Definition: tsid_biped.py:155
tsid_biped.TsidBiped.LF
LF
Definition: tsid_biped.py:78
tsid_biped.TsidBiped.copTask
copTask
Definition: tsid_biped.py:161
tsid_biped.TsidBiped.robot_display
robot_display
Definition: tsid_biped.py:176
tsid_biped.TsidBiped.sampleLF
sampleLF
Definition: tsid_biped.py:147
tsid_biped.TsidBiped.q0
q0
Definition: tsid_biped.py:27
tsid_biped.TsidBiped.display
def display(self, q)
Definition: tsid_biped.py:209
tsid::InverseDynamicsFormulationAccForce
Definition: inverse-dynamics-formulation-acc-force.hpp:40
tsid_biped.TsidBiped.conf
conf
Definition: tsid_biped.py:20
tsid_biped.TsidBiped.get_placement_LF
def get_placement_LF(self)
Definition: tsid_biped.py:219
tsid_biped.TsidBiped.trajRF
trajRF
Definition: tsid_biped.py:120
tsid_biped.TsidBiped.rightFootTask
rightFootTask
Definition: tsid_biped.py:115
tsid_biped.TsidBiped.tau_min
tau_min
Definition: tsid_biped.py:124
tsid_biped.TsidBiped.remove_contact_LF
def remove_contact_LF(self, transition_time=0.0)
Definition: tsid_biped.py:271
tsid_biped.TsidBiped.solver
solver
Definition: tsid_biped.py:157
tsid_biped.TsidBiped.trajLF
trajLF
Definition: tsid_biped.py:112
tsid_biped.TsidBiped.add_contact_RF
def add_contact_RF(self, transition_time=0.0)
Definition: tsid_biped.py:279
tsid_biped.TsidBiped
Definition: tsid_biped.py:11
tsid_biped.TsidBiped.set_LF_3d_ref
def set_LF_3d_ref(self, pos, vel, acc)
Definition: tsid_biped.py:240
tsid_biped.TsidBiped.set_com_ref
def set_com_ref(self, pos, vel, acc)
Definition: tsid_biped.py:225
tsid_biped.TsidBiped.actuationBoundsTask
actuationBoundsTask
Definition: tsid_biped.py:166
tsid_biped.TsidBiped.v_min
v_min
Definition: tsid_biped.py:134


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17