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


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:51