tsid_manipulator.py
Go to the documentation of this file.
1 import os
2 import subprocess
3 import time
4 
5 import gepetto.corbaserver
6 import numpy as np
7 import pinocchio as se3
8 
9 import tsid
10 
11 
13  """Standard TSID formulation for a robot manipulator
14  - end-effector task
15  - Postural task
16  - torque limits
17  - pos/vel limits
18  """
19 
20  def __init__(self, conf, viewer=True):
21  self.conf = conf
22  self.robot = tsid.RobotWrapper(conf.urdf, [conf.path], False)
23  robot = self.robot
24  self.model = model = robot.model()
25  try:
26  # q = se3.getNeutralConfiguration(model, conf.srdf, False)
27  se3.loadReferenceConfigurations(model, conf.srdf, False)
28  q = model.referenceConfigurations["default"]
29  # q = model.referenceConfigurations["half_sitting"]
30  except Exception:
31  q = conf.q0
32  # q = np.array(np.zeros(robot.nv)).T
33  v = np.zeros(robot.nv)
34 
35  assert model.existFrame(conf.ee_frame_name)
36 
37  formulation = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False)
38  formulation.computeProblemData(0.0, q, v)
39 
40  postureTask = tsid.TaskJointPosture("task-posture", robot)
41  postureTask.setKp(conf.kp_posture * np.ones(robot.nv))
42  postureTask.setKd(2.0 * np.sqrt(conf.kp_posture) * np.ones(robot.nv))
43  formulation.addMotionTask(postureTask, conf.w_posture, 1, 0.0)
44 
45  self.eeTask = tsid.TaskSE3Equality(
46  "task-ee", self.robot, self.conf.ee_frame_name
47  )
48  self.eeTask.setKp(self.conf.kp_ee * np.ones(6))
49  self.eeTask.setKd(2.0 * np.sqrt(self.conf.kp_ee) * np.ones(6))
50  self.eeTask.setMask(conf.ee_task_mask)
51  self.eeTask.useLocalFrame(conf.ee_task_local_frame)
52  self.EE = model.getFrameId(conf.ee_frame_name)
53  H_ee_ref = self.robot.framePosition(formulation.data(), self.EE)
54  self.trajEE = tsid.TrajectorySE3Constant("traj-ee", H_ee_ref)
55  formulation.addMotionTask(self.eeTask, conf.w_ee, 1, 0.0)
56 
57  self.tau_max = conf.tau_max_scaling * model.effortLimit
58  self.tau_min = -self.tau_max
59  actuationBoundsTask = tsid.TaskActuationBounds("task-actuation-bounds", robot)
60  actuationBoundsTask.setBounds(self.tau_min, self.tau_max)
61  if conf.w_torque_bounds > 0.0:
62  formulation.addActuationTask(
63  actuationBoundsTask, conf.w_torque_bounds, 0, 0.0
64  )
65 
66  jointBoundsTask = tsid.TaskJointBounds("task-joint-bounds", robot, conf.dt)
67  self.v_max = conf.v_max_scaling * model.velocityLimit
68  self.v_min = -self.v_max
69  jointBoundsTask.setVelocityBounds(self.v_min, self.v_max)
70  if conf.w_joint_bounds > 0.0:
71  formulation.addMotionTask(jointBoundsTask, conf.w_joint_bounds, 0, 0.0)
72 
73  trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q)
74  postureTask.setReference(trajPosture.computeNext())
75 
76  solver = tsid.SolverHQuadProgFast("qp solver")
77  solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)
78 
79  self.trajPosture = trajPosture
80  self.postureTask = postureTask
81  self.actuationBoundsTask = actuationBoundsTask
82  self.jointBoundsTask = jointBoundsTask
83  self.formulation = formulation
84  self.solver = solver
85  self.q = q
86  self.v = v
87 
88  # for gepetto viewer
89  if viewer:
90  self.robot_display = se3.RobotWrapper.BuildFromURDF(
91  conf.urdf,
92  [
93  conf.path,
94  ],
95  )
96  n = subprocess.getstatusoutput(
97  "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l"
98  )
99  if int(n[1]) == 0:
100  os.system("gepetto-gui &")
101  time.sleep(1)
102  gepetto.corbaserver.Client()
103  self.robot_display.initViewer(loadModel=True)
104  self.robot_display.displayCollisions(False)
105  self.robot_display.displayVisuals(True)
106  self.robot_display.display(q)
107  self.gui = self.robot_display.viewer.gui
108 
109  # self.gui.setCameraTransform(0, conf.CAMERA_TRANSFORM)
110 
111  def integrate_dv(self, q, v, dv, dt):
112  v_mean = v + 0.5 * dt * dv
113  v += dt * dv
114  q = se3.integrate(self.model, q, dt * v_mean)
115  return q, v
tsid_manipulator.TsidManipulator
Definition: tsid_manipulator.py:12
tsid_manipulator.TsidManipulator.robot_display
robot_display
Definition: tsid_manipulator.py:90
tsid_manipulator.TsidManipulator.conf
conf
Definition: tsid_manipulator.py:21
tsid_manipulator.TsidManipulator.trajEE
trajEE
Definition: tsid_manipulator.py:54
tsid_manipulator.TsidManipulator.v_max
v_max
Definition: tsid_manipulator.py:67
tsid_manipulator.TsidManipulator.tau_min
tau_min
Definition: tsid_manipulator.py:58
tsid_manipulator.TsidManipulator.robot
robot
Definition: tsid_manipulator.py:22
tsid_manipulator.TsidManipulator.formulation
formulation
Definition: tsid_manipulator.py:83
tsid_manipulator.TsidManipulator.solver
solver
Definition: tsid_manipulator.py:84
tsid_manipulator.TsidManipulator.v_min
v_min
Definition: tsid_manipulator.py:68
tsid_manipulator.TsidManipulator.actuationBoundsTask
actuationBoundsTask
Definition: tsid_manipulator.py:81
tsid_manipulator.TsidManipulator.tau_max
tau_max
Definition: tsid_manipulator.py:57
tsid_manipulator.TsidManipulator.eeTask
eeTask
Definition: tsid_manipulator.py:45
tsid_manipulator.TsidManipulator.v
v
Definition: tsid_manipulator.py:86
tsid_manipulator.TsidManipulator.integrate_dv
def integrate_dv(self, q, v, dv, dt)
Definition: tsid_manipulator.py:111
tsid_manipulator.TsidManipulator.trajPosture
trajPosture
Definition: tsid_manipulator.py:79
display
tsid_manipulator.TsidManipulator.q
q
Definition: tsid_manipulator.py:85
tsid::InverseDynamicsFormulationAccForce
Definition: inverse-dynamics-formulation-acc-force.hpp:40
tsid_manipulator.TsidManipulator.model
model
Definition: tsid_manipulator.py:24
tsid_manipulator.TsidManipulator.__init__
def __init__(self, conf, viewer=True)
Definition: tsid_manipulator.py:20
tsid_manipulator.TsidManipulator.gui
gui
Definition: tsid_manipulator.py:107
tsid_manipulator.TsidManipulator.postureTask
postureTask
Definition: tsid_manipulator.py:80
tsid_manipulator.TsidManipulator.jointBoundsTask
jointBoundsTask
Definition: tsid_manipulator.py:82
tsid_manipulator.TsidManipulator.EE
EE
Definition: tsid_manipulator.py:52


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