5 import gepetto.corbaserver
7 import pinocchio
as se3
13 """Standard TSID formulation for a robot manipulator
22 self.
robot = tsid.RobotWrapper(conf.urdf, [conf.path],
False)
24 self.
model = model = robot.model()
27 se3.loadReferenceConfigurations(model, conf.srdf,
False)
28 q = model.referenceConfigurations[
"default"]
33 v = np.zeros(robot.nv)
35 assert model.existFrame(conf.ee_frame_name)
38 formulation.computeProblemData(0.0, q, v)
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)
46 "task-ee", self.
robot, self.
conf.ee_frame_name
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)
57 self.
tau_max = conf.tau_max_scaling * model.effortLimit
59 actuationBoundsTask = tsid.TaskActuationBounds(
"task-actuation-bounds", robot)
61 if conf.w_torque_bounds > 0.0:
62 formulation.addActuationTask(
63 actuationBoundsTask, conf.w_torque_bounds, 0, 0.0
66 jointBoundsTask = tsid.TaskJointBounds(
"task-joint-bounds", robot, conf.dt)
67 self.
v_max = conf.v_max_scaling * model.velocityLimit
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)
73 trajPosture = tsid.TrajectoryEuclidianConstant(
"traj_joint", q)
74 postureTask.setReference(trajPosture.computeNext())
76 solver = tsid.SolverHQuadProgFast(
"qp solver")
77 solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)
96 n = subprocess.getstatusoutput(
97 "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l"
100 os.system(
"gepetto-gui &")
102 gepetto.corbaserver.Client()
112 v_mean = v + 0.5 * dt * dv
114 q = se3.integrate(self.
model, q, dt * v_mean)