sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
appli_no_admittance.py
Go to the documentation of this file.
1 # flake8: noqa
2 from math import sqrt
3 
4 import numpy as np
5 from dynamic_graph import plug
6 from dynamic_graph.sot.core import (
7  SOT,
8  Derivator_of_Vector,
9  FeaturePosture,
10  MatrixHomoToPoseQuaternion,
11  Task,
12 )
13 from dynamic_graph.sot.core.matrix_util import matrixToTuple
14 from dynamic_graph.sot.core.meta_tasks_kine import (
15  MetaTaskKine6d,
16  MetaTaskKineCom,
17  gotoNd,
18 )
19 from dynamic_graph.sot.dynamic_pinocchio import DynamicPinocchio
20 from dynamic_graph.tracer_real_time import TracerRealTime
21 
22 import dynamic_graph.sot_talos_balance.talos.base_estimator_conf as base_estimator_conf
23 import dynamic_graph.sot_talos_balance.talos.control_manager_conf as cm_conf
24 import dynamic_graph.sot_talos_balance.talos.ft_calibration_conf as ft_conf
25 import dynamic_graph.sot_talos_balance.talos.parameter_server_conf as param_server_conf
27 
28 cm_conf.CTRL_MAX = 10.0 # temporary hack
29 
30 robot.timeStep = robot.device.getTimeStep()
31 dt = robot.timeStep
32 
33 # --- Pendulum parameters
34 robot_name = "robot"
35 robot.dynamic.com.recompute(0)
36 robotDim = robot.dynamic.getDimension()
37 mass = robot.dynamic.data.mass[0]
38 h = robot.dynamic.com.value[2]
39 g = 9.81
40 omega = sqrt(g / h)
41 
42 # --- Parameter server
43 robot.param_server = create_parameter_server(param_server_conf, dt)
44 
45 # --- Initial feet and waist
46 robot.dynamic.createOpPoint("LF", robot.OperationalPointsMap["left-ankle"])
47 robot.dynamic.createOpPoint("RF", robot.OperationalPointsMap["right-ankle"])
48 robot.dynamic.createOpPoint("WT", robot.OperationalPointsMap["waist"])
49 robot.dynamic.LF.recompute(0)
50 robot.dynamic.RF.recompute(0)
51 robot.dynamic.WT.recompute(0)
52 
53 # -------------------------- DESIRED TRAJECTORY --------------------------
54 
55 folder = None
56 if test_folder is not None:
57  if sot_talos_balance_folder:
58  from rospkg import RosPack
59 
60  rospack = RosPack()
61 
62  folder = rospack.get_path("sot-talos-balance") + "/data/" + test_folder
63  else:
64  folder = test_folder
65  if folder[-1] != "/":
66  folder += "/"
67 
68 # --- Trajectory generators
69 
70 # --- General trigger
71 robot.triggerTrajGen = BooleanIdentity("triggerTrajGen")
72 robot.triggerTrajGen.sin.value = 0
73 
74 # --- CoM
75 robot.comTrajGen = create_com_trajectory_generator(dt, robot)
76 robot.comTrajGen.x.recompute(0) # trigger computation of initial value
77 plug(robot.triggerTrajGen.sout, robot.comTrajGen.trigger)
78 
79 # --- Left foot
80 robot.lfTrajGen = create_pose_rpy_trajectory_generator(dt, robot, "LF")
81 robot.lfTrajGen.x.recompute(0) # trigger computation of initial value
82 
83 robot.lfToMatrix = PoseRollPitchYawToMatrixHomo("lf2m")
84 plug(robot.lfTrajGen.x, robot.lfToMatrix.sin)
85 plug(robot.triggerTrajGen.sout, robot.lfTrajGen.trigger)
86 
87 # --- Right foot
88 robot.rfTrajGen = create_pose_rpy_trajectory_generator(dt, robot, "RF")
89 robot.rfTrajGen.x.recompute(0) # trigger computation of initial value
90 
91 robot.rfToMatrix = PoseRollPitchYawToMatrixHomo("rf2m")
92 plug(robot.rfTrajGen.x, robot.rfToMatrix.sin)
93 plug(robot.triggerTrajGen.sout, robot.rfTrajGen.trigger)
94 
95 # --- ZMP
96 robot.zmpTrajGen = create_zmp_trajectory_generator(dt, robot)
97 robot.zmpTrajGen.x.recompute(0) # trigger computation of initial value
98 plug(robot.triggerTrajGen.sout, robot.zmpTrajGen.trigger)
99 
100 # --- Waist
101 robot.waistTrajGen = create_orientation_rpy_trajectory_generator(dt, robot, "WT")
102 robot.waistTrajGen.x.recompute(0) # trigger computation of initial value
103 
104 robot.waistMix = Mix_of_vector("waistMix")
105 robot.waistMix.setSignalNumber(3)
106 robot.waistMix.addSelec(1, 0, 3)
107 robot.waistMix.addSelec(2, 3, 3)
108 robot.waistMix.default.value = [0.0] * 6
109 robot.waistMix.signal("sin1").value = [0.0] * 3
110 plug(robot.waistTrajGen.x, robot.waistMix.signal("sin2"))
111 
112 robot.waistToMatrix = PoseRollPitchYawToMatrixHomo("w2m")
113 plug(robot.waistMix.sout, robot.waistToMatrix.sin)
114 plug(robot.triggerTrajGen.sout, robot.waistTrajGen.trigger)
115 
116 # --- Load files
117 if folder is not None:
118  robot.comTrajGen.playTrajectoryFile(folder + "CoM.dat")
119  robot.lfTrajGen.playTrajectoryFile(folder + "LeftFoot.dat")
120  robot.rfTrajGen.playTrajectoryFile(folder + "RightFoot.dat")
121  # robot.zmpTrajGen.playTrajectoryFile(folder + 'ZMP.dat')
122  robot.waistTrajGen.playTrajectoryFile(folder + "WaistOrientation.dat")
123 
124 # --- Interface with controller entities
125 
126 wp = DummyWalkingPatternGenerator("dummy_wp")
127 wp.init()
128 wp.omega.value = omega
129 plug(robot.waistToMatrix.sout, wp.waist)
130 plug(robot.lfToMatrix.sout, wp.footLeft)
131 plug(robot.rfToMatrix.sout, wp.footRight)
132 plug(robot.comTrajGen.x, wp.com)
133 plug(robot.comTrajGen.dx, wp.vcom)
134 plug(robot.comTrajGen.ddx, wp.acom)
135 # if folder is not None:
136 # plug(robot.zmpTrajGen.x, wp.zmp)
137 
138 robot.wp = wp
139 
140 # --- Compute the values to use them in initialization
141 robot.wp.comDes.recompute(0)
142 robot.wp.dcmDes.recompute(0)
143 robot.wp.zmpDes.recompute(0)
144 
145 # -------------------------- ESTIMATION --------------------------
146 
147 # --- Base Estimation
148 robot.device_filters = create_device_filters(robot, dt)
149 robot.imu_filters = create_imu_filters(robot, dt)
150 robot.base_estimator = create_base_estimator(robot, dt, base_estimator_conf)
151 
152 robot.m2qLF = MatrixHomoToPoseQuaternion("m2qLF")
153 plug(robot.dynamic.LF, robot.m2qLF.sin)
154 plug(robot.m2qLF.sout, robot.base_estimator.lf_ref_xyzquat)
155 robot.m2qRF = MatrixHomoToPoseQuaternion("m2qRF")
156 plug(robot.dynamic.RF, robot.m2qRF.sin)
157 plug(robot.m2qRF.sout, robot.base_estimator.rf_ref_xyzquat)
158 
159 # robot.be_filters = create_be_filters(robot, dt)
160 
161 # --- Conversion
162 e2q = EulerToQuat("e2q")
163 plug(robot.base_estimator.q, e2q.euler)
164 robot.e2q = e2q
165 
166 # --- Kinematic computations
167 robot.rdynamic = DynamicPinocchio("real_dynamics")
168 robot.rdynamic.setModel(robot.dynamic.model)
169 robot.rdynamic.setData(robot.rdynamic.model.createData())
170 plug(robot.base_estimator.q, robot.rdynamic.position)
171 robot.rdynamic.velocity.value = [0.0] * robotDim
172 robot.rdynamic.acceleration.value = [0.0] * robotDim
173 
174 # --- CoM Estimation
175 cdc_estimator = DcmEstimator("cdc_estimator")
176 cdc_estimator.init(dt, robot_name)
177 plug(robot.e2q.quaternion, cdc_estimator.q)
178 plug(robot.base_estimator.v, cdc_estimator.v)
179 robot.cdc_estimator = cdc_estimator
180 
181 # --- DCM Estimation
182 estimator = DummyDcmEstimator("dummy")
183 plug(robot.wp.omegaDes, estimator.omega)
184 estimator.mass.value = 1.0
185 plug(robot.cdc_estimator.c, estimator.com)
186 plug(robot.cdc_estimator.dc, estimator.momenta)
187 estimator.init()
188 robot.estimator = estimator
189 
190 # --- Force calibration
191 robot.ftc = create_ft_calibrator(robot, ft_conf)
192 
193 # --- ZMP estimation
194 zmp_estimator = SimpleZmpEstimator("zmpEst")
195 robot.rdynamic.createOpPoint("sole_LF", "left_sole_link")
196 robot.rdynamic.createOpPoint("sole_RF", "right_sole_link")
197 plug(robot.rdynamic.sole_LF, zmp_estimator.poseLeft)
198 plug(robot.rdynamic.sole_RF, zmp_estimator.poseRight)
199 plug(robot.ftc.left_foot_force_out, zmp_estimator.wrenchLeft)
200 plug(robot.ftc.right_foot_force_out, zmp_estimator.wrenchRight)
201 zmp_estimator.init()
202 robot.zmp_estimator = zmp_estimator
203 
204 # --- Control Manager
205 robot.cm = create_ctrl_manager(cm_conf, dt, robot_name="robot")
206 robot.cm.addCtrlMode("sot_input")
207 robot.cm.setCtrlMode("all", "sot_input")
208 robot.cm.addEmergencyStopSIN("zmp")
209 
210 # -------------------------- SOT CONTROL --------------------------
211 
212 # --- Upper body
213 robot.taskUpperBody = Task("task_upper_body")
214 robot.taskUpperBody.feature = FeaturePosture("feature_upper_body")
215 
216 q = list(robot.dynamic.position.value)
217 robot.taskUpperBody.feature.state.value = q
218 robot.taskUpperBody.feature.posture.value = q
219 
220 robotDim = robot.dynamic.getDimension() # 38
221 for i in range(18, robotDim):
222  robot.taskUpperBody.feature.selectDof(i, True)
223 
224 robot.taskUpperBody.controlGain.value = 100.0
225 robot.taskUpperBody.add(robot.taskUpperBody.feature.name)
226 plug(robot.dynamic.position, robot.taskUpperBody.feature.state)
227 
228 # --- CONTACTS
229 # define contactLF and contactRF
230 robot.contactLF = MetaTaskKine6d(
231  "contactLF", robot.dynamic, "LF", robot.OperationalPointsMap["left-ankle"]
232 )
233 robot.contactLF.feature.frame("desired")
234 robot.contactLF.gain.setConstant(300)
235 plug(robot.wp.footLeftDes, robot.contactLF.featureDes.position) # .errorIN?
236 locals()["contactLF"] = robot.contactLF
237 
238 robot.contactRF = MetaTaskKine6d(
239  "contactRF", robot.dynamic, "RF", robot.OperationalPointsMap["right-ankle"]
240 )
241 robot.contactRF.feature.frame("desired")
242 robot.contactRF.gain.setConstant(300)
243 plug(robot.wp.footRightDes, robot.contactRF.featureDes.position) # .errorIN?
244 locals()["contactRF"] = robot.contactRF
245 
246 # --- COM
247 robot.taskCom = MetaTaskKineCom(robot.dynamic)
248 plug(robot.wp.comDes, robot.taskCom.featureDes.errorIN)
249 # plug(robot.wp.vcomDes,robot.taskCom.featureDes.errordotIN)
250 robot.taskCom.task.controlGain.value = 100.0
251 # robot.taskCom.task.setWithDerivative(True)
252 
253 # --- Waist
254 robot.keepWaist = MetaTaskKine6d(
255  "keepWaist", robot.dynamic, "WT", robot.OperationalPointsMap["waist"]
256 )
257 robot.keepWaist.feature.frame("desired")
258 robot.keepWaist.gain.setConstant(300)
259 plug(robot.wp.waistDes, robot.keepWaist.featureDes.position)
260 robot.keepWaist.feature.selec.value = "111000"
261 locals()["keepWaist"] = robot.keepWaist
262 
263 # --- SOT solver
264 robot.sot = SOT("sot")
265 robot.sot.setSize(robot.dynamic.getDimension())
266 
267 # --- Plug SOT control to device through control manager
268 plug(robot.sot.control, robot.cm.ctrl_sot_input)
269 plug(robot.cm.u_safe, robot.device.control)
270 
271 robot.sot.push(robot.taskUpperBody.name)
272 robot.sot.push(robot.contactRF.task.name)
273 robot.sot.push(robot.contactLF.task.name)
274 robot.sot.push(robot.taskCom.task.name)
275 robot.sot.push(robot.keepWaist.task.name)
276 # robot.sot.push(robot.taskPos.name)
277 # robot.device.control.recompute(0) # this crashes as it employs joint sensors which are not ready yet
278 
279 # --- Fix robot.dynamic inputs
280 plug(robot.device.velocity, robot.dynamic.velocity)
281 robot.dvdt = Derivator_of_Vector("dv_dt")
282 robot.dvdt.dt.value = dt
283 plug(robot.device.velocity, robot.dvdt.sin)
284 plug(robot.dvdt.sout, robot.dynamic.acceleration)
285 
286 # -------------------------- PLOTS --------------------------
287 
288 # --- ROS PUBLISHER
289 robot.publisher = create_rospublish(robot, "robot_publisher")
290 
291 create_topic(robot.publisher, robot.device, "state", robot=robot, data_type="vector")
293  robot.publisher, robot.base_estimator, "q", robot=robot, data_type="vector"
294 )
295 
297  robot.publisher, robot.comTrajGen, "x", robot=robot, data_type="vector"
298 ) # generated CoM
300  robot.publisher, robot.comTrajGen, "dx", robot=robot, data_type="vector"
301 ) # generated CoM velocity
303  robot.publisher, robot.comTrajGen, "ddx", robot=robot, data_type="vector"
304 ) # generated CoM acceleration
305 
307  robot.publisher, robot.wp, "comDes", robot=robot, data_type="vector"
308 ) # desired CoM
309 
311  robot.publisher, robot.cdc_estimator, "c", robot=robot, data_type="vector"
312 ) # estimated CoM
314  robot.publisher, robot.cdc_estimator, "dc", robot=robot, data_type="vector"
315 ) # estimated CoM velocity
316 
318  robot.publisher, robot.dynamic, "com", robot=robot, data_type="vector"
319 ) # resulting SOT CoM
320 
322  robot.publisher, robot.wp, "dcmDes", robot=robot, data_type="vector"
323 ) # desired DCM
325  robot.publisher, robot.estimator, "dcm", robot=robot, data_type="vector"
326 ) # estimated DCM
327 
329  robot.publisher, robot.zmpTrajGen, "x", robot=robot, data_type="vector"
330 ) # generated ZMP
332  robot.publisher, robot.wp, "zmpDes", robot=robot, data_type="vector"
333 ) # desired ZMP
335  robot.publisher, robot.dynamic, "zmp", robot=robot, data_type="vector"
336 ) # SOT ZMP
338  robot.publisher, robot.zmp_estimator, "zmp", robot=robot, data_type="vector"
339 ) # estimated ZMP
340 
341 # create_topic(robot.publisher, robot.device, 'forceLLEG', robot = robot, data_type='vector') # measured left wrench
342 # create_topic(robot.publisher, robot.device, 'forceRLEG', robot = robot, data_type='vector') # measured right wrench
343 
344 # create_topic(robot.publisher, robot.device_filters.ft_LF_filter, 'x_filtered', robot = robot, data_type='vector') # filtered left wrench
345 # create_topic(robot.publisher, robot.device_filters.ft_RF_filter, 'x_filtered', robot = robot, data_type='vector') # filtered right wrench
346 
348  robot.publisher, robot.waistTrajGen, "x", robot=robot, data_type="vector"
349 ) # desired waist orientation
350 
352  robot.publisher, robot.lfTrajGen, "x", robot=robot, data_type="vector"
353 ) # desired left foot pose
355  robot.publisher, robot.rfTrajGen, "x", robot=robot, data_type="vector"
356 ) # desired right foot pose
357 
359  robot.publisher, robot.ftc, "left_foot_force_out", robot=robot, data_type="vector"
360 ) # calibrated left wrench
362  robot.publisher, robot.ftc, "right_foot_force_out", robot=robot, data_type="vector"
363 ) # calibrated right wrench
364 
366  robot.publisher, robot.dynamic, "LF", robot=robot, data_type="matrixHomo"
367 ) # left foot
369  robot.publisher, robot.dynamic, "RF", robot=robot, data_type="matrixHomo"
370 ) # right foot
371 
372 
377 
378 # addTrace(robot.tracer, robot.wp, 'comDes') # desired CoM
379 
380 # addTrace(robot.tracer, robot.cdc_estimator, 'c') # estimated CoM
381 # addTrace(robot.tracer, robot.cdc_estimator, 'dc') # estimated CoM velocity
382 
383 # addTrace(robot.tracer, robot.com_admittance_control, 'comRef') # reference CoM
384 # addTrace(robot.tracer, robot.dynamic, 'com') # resulting SOT CoM
385 
386 # addTrace(robot.tracer, robot.dcm_control, 'dcmDes') # desired DCM
387 # addTrace(robot.tracer, robot.estimator, 'dcm') # estimated DCM
388 
389 # addTrace(robot.tracer, robot.dcm_control, 'zmpDes') # desired ZMP
390 # addTrace(robot.tracer, robot.dynamic, 'zmp') # SOT ZMP
391 # addTrace(robot.tracer, robot.zmp_estimator, 'zmp') # estimated ZMP
392 # addTrace(robot.tracer, robot.dcm_control, 'zmpRef') # reference ZMP
393 
394 # addTrace(robot.tracer, robot.ftc, 'left_foot_force_out') # calibrated left wrench
395 # addTrace(robot.tracer, robot.ftc, 'right_foot_force_out') # calibrated right wrench
396 
397 # addTrace(robot.tracer, robot.dynamic, 'LF') # left foot
398 # addTrace(robot.tracer, robot.dynamic, 'RF') # right foot
399 
400 # robot.tracer.start()
sot_talos_balance.create_entities_utils.create_ctrl_manager
def create_ctrl_manager(conf, dt, robot_name="robot")
Definition: create_entities_utils.py:341
create_entities_utils
sot_talos_balance.create_entities_utils.create_ft_calibrator
def create_ft_calibrator(robot, conf)
Definition: create_entities_utils.py:683
sot_talos_balance.create_entities_utils.create_base_estimator
def create_base_estimator(robot, dt, conf, robot_name="robot")
Definition: create_entities_utils.py:352
sot_talos_balance.create_entities_utils.create_com_trajectory_generator
def create_com_trajectory_generator(dt, robot)
Definition: create_entities_utils.py:120
sot_talos_balance.create_entities_utils.create_pose_rpy_trajectory_generator
def create_pose_rpy_trajectory_generator(dt, robot, signal_name)
Definition: create_entities_utils.py:162
sot_talos_balance.create_entities_utils.create_zmp_trajectory_generator
def create_zmp_trajectory_generator(dt, robot)
Definition: create_entities_utils.py:128
sot_talos_balance.create_entities_utils.create_topic
def create_topic(rospub, entity, signalName, robot=None, data_type="vector")
Definition: create_entities_utils.py:454
sot_talos_balance.create_entities_utils.create_orientation_rpy_trajectory_generator
def create_orientation_rpy_trajectory_generator(dt, robot, signal_name)
Definition: create_entities_utils.py:150
sot_talos_balance.create_entities_utils.create_parameter_server
def create_parameter_server(conf, dt, robot_name="robot")
Definition: create_entities_utils.py:619
sot_talos_balance.create_entities_utils.create_imu_filters
def create_imu_filters(robot, dt)
Definition: create_entities_utils.py:388
sot_talos_balance.create_entities_utils.create_rospublish
def create_rospublish(robot, name)
Definition: create_entities_utils.py:446
sot_talos_balance.create_entities_utils.create_device_filters
def create_device_filters(robot, dt)
Definition: create_entities_utils.py:279