sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
appli_dcm_zmp_control_flex.py
Go to the documentation of this file.
1 # flake8: noqa
2 from math import sqrt
3 
4 import numpy as np
5 
6 import dynamic_graph.sot_talos_balance.talos.base_estimator_conf as base_estimator_conf
7 import dynamic_graph.sot_talos_balance.talos.control_manager_conf as cm_conf
8 import dynamic_graph.sot_talos_balance.talos.ft_calibration_conf as ft_conf
9 import dynamic_graph.sot_talos_balance.talos.hip_flexibility_compensation_conf as hipFlexCompConfig
10 import dynamic_graph.sot_talos_balance.talos.parameter_server_conf as param_server_conf
11 from dynamic_graph import plug
12 from dynamic_graph.sot.core import (
13  SOT,
14  Derivator_of_Vector,
15  FeaturePosture,
16  MatrixHomoToPoseQuaternion,
17  Task,
18 )
19 from dynamic_graph.sot.core.matrix_util import matrixToTuple
20 from dynamic_graph.sot.core.meta_tasks_kine import (
21  MetaTaskKine6d,
22  MetaTaskKineCom,
23  gotoNd,
24 )
25 from dynamic_graph.sot.dynamic_pinocchio import DynamicPinocchio
26 from dynamic_graph.tracer_real_time import TracerRealTime
28 
29 cm_conf.CTRL_MAX = 10.0 # temporary hack
30 
31 robot.timeStep = robot.device.getTimeStep()
32 dt = robot.timeStep
33 robot.device.setControlInputType("noInteg")
34 
35 # --- Pendulum parameters
36 robot_name = "robot"
37 robot.dynamic.com.recompute(0)
38 robotDim = robot.dynamic.getDimension()
39 mass = robot.dynamic.data.mass[0]
40 h = robot.dynamic.com.value[2]
41 g = 9.81
42 omega = sqrt(g / h)
43 
44 # --- Parameter server
45 robot.param_server = create_parameter_server(param_server_conf, dt)
46 
47 # --- Initial feet and waist
48 robot.dynamic.createOpPoint("LF", robot.OperationalPointsMap["left-ankle"])
49 robot.dynamic.createOpPoint("RF", robot.OperationalPointsMap["right-ankle"])
50 robot.dynamic.createOpPoint("WT", robot.OperationalPointsMap["waist"])
51 robot.dynamic.LF.recompute(0)
52 robot.dynamic.RF.recompute(0)
53 robot.dynamic.WT.recompute(0)
54 
55 # -------------------------- DESIRED TRAJECTORY --------------------------
56 
57 folder = None
58 if test_folder is not None:
59  if sot_talos_balance_folder:
60  from rospkg import RosPack
61 
62  rospack = RosPack()
63 
64  folder = rospack.get_path("sot-talos-balance") + "/data/" + test_folder
65  else:
66  folder = test_folder
67  if folder[-1] != "/":
68  folder += "/"
69 
70 # --- Trajectory generators
71 
72 # --- General trigger
73 robot.triggerTrajGen = BooleanIdentity("triggerTrajGen")
74 set_trigger(robot, False)
75 
76 # --- CoM
77 robot.comTrajGen = create_com_trajectory_generator(dt, robot)
78 robot.comTrajGen.x.recompute(0) # trigger computation of initial value
79 plug(robot.triggerTrajGen.sout, robot.comTrajGen.trigger)
80 
81 # --- Left foot
82 robot.lfTrajGen = create_pose_rpy_trajectory_generator(dt, robot, "LF")
83 robot.lfTrajGen.x.recompute(0) # trigger computation of initial value
84 
85 robot.lfToMatrix = PoseRollPitchYawToMatrixHomo("lf2m")
86 plug(robot.lfTrajGen.x, robot.lfToMatrix.sin)
87 plug(robot.triggerTrajGen.sout, robot.lfTrajGen.trigger)
88 
89 # --- Right foot
90 robot.rfTrajGen = create_pose_rpy_trajectory_generator(dt, robot, "RF")
91 robot.rfTrajGen.x.recompute(0) # trigger computation of initial value
92 
93 robot.rfToMatrix = PoseRollPitchYawToMatrixHomo("rf2m")
94 plug(robot.rfTrajGen.x, robot.rfToMatrix.sin)
95 plug(robot.triggerTrajGen.sout, robot.rfTrajGen.trigger)
96 
97 # --- ZMP
98 robot.zmpTrajGen = create_zmp_trajectory_generator(dt, robot)
99 robot.zmpTrajGen.x.recompute(0) # trigger computation of initial value
100 plug(robot.triggerTrajGen.sout, robot.zmpTrajGen.trigger)
101 
102 # --- Waist
103 robot.waistTrajGen = create_orientation_rpy_trajectory_generator(dt, robot, "WT")
104 robot.waistTrajGen.x.recompute(0) # trigger computation of initial value
105 
106 robot.waistMix = Mix_of_vector("waistMix")
107 robot.waistMix.setSignalNumber(3)
108 robot.waistMix.addSelec(1, 0, 3)
109 robot.waistMix.addSelec(2, 3, 3)
110 robot.waistMix.default.value = [0.0] * 6
111 robot.waistMix.signal("sin1").value = [0.0] * 3
112 plug(robot.waistTrajGen.x, robot.waistMix.signal("sin2"))
113 
114 robot.waistToMatrix = PoseRollPitchYawToMatrixHomo("w2m")
115 plug(robot.waistMix.sout, robot.waistToMatrix.sin)
116 plug(robot.triggerTrajGen.sout, robot.waistTrajGen.trigger)
117 
118 # --- Phase
119 robot.phaseTrajGen = create_scalar_trajectory_generator(dt, 0.0, "phaseTrajGen")
120 robot.phaseTrajGen.x.recompute(0) # trigger computation of initial value
121 robot.phaseScalar = Component_of_vector("phase_scalar")
122 robot.phaseScalar.setIndex(0)
123 plug(robot.phaseTrajGen.x, robot.phaseScalar.sin)
124 robot.phaseInt = RoundDoubleToInt("phase_int")
125 plug(robot.phaseScalar.sout, robot.phaseInt.sin)
126 plug(robot.triggerTrajGen.sout, robot.phaseTrajGen.trigger)
127 
128 # --- Load files
129 load_folder(robot, folder)
130 
131 # --- Interface with controller entities
132 
133 wp = DummyWalkingPatternGenerator("dummy_wp")
134 wp.init()
135 wp.omega.value = omega
136 plug(robot.waistToMatrix.sout, wp.waist)
137 plug(robot.lfToMatrix.sout, wp.footLeft)
138 plug(robot.rfToMatrix.sout, wp.footRight)
139 plug(robot.comTrajGen.x, wp.com)
140 plug(robot.comTrajGen.dx, wp.vcom)
141 plug(robot.comTrajGen.ddx, wp.acom)
142 # if folder is not None:
143 # plug(robot.zmpTrajGen.x, wp.zmp)
144 
145 robot.wp = wp
146 
147 # --- Compute the values to use them in initialization
148 robot.wp.comDes.recompute(0)
149 robot.wp.dcmDes.recompute(0)
150 robot.wp.zmpDes.recompute(0)
151 
152 # -------------------------- ESTIMATION --------------------------
153 
154 # --- Base Estimation
155 robot.device_filters = create_device_filters(robot, dt)
156 robot.imu_filters = create_imu_filters(robot, dt)
157 robot.base_estimator = create_base_estimator(robot, dt, base_estimator_conf)
158 
159 robot.m2qLF = MatrixHomoToPoseQuaternion("m2qLF")
160 plug(robot.dynamic.LF, robot.m2qLF.sin)
161 plug(robot.m2qLF.sout, robot.base_estimator.lf_ref_xyzquat)
162 robot.m2qRF = MatrixHomoToPoseQuaternion("m2qRF")
163 plug(robot.dynamic.RF, robot.m2qRF.sin)
164 plug(robot.m2qRF.sout, robot.base_estimator.rf_ref_xyzquat)
165 
166 # robot.be_filters = create_be_filters(robot, dt)
167 
168 # --- Conversion
169 e2q = EulerToQuat("e2q")
170 plug(robot.base_estimator.q, e2q.euler)
171 robot.e2q = e2q
172 
173 # --- Kinematic computations
174 robot.rdynamic = DynamicPinocchio("real_dynamics")
175 robot.rdynamic.setModel(robot.dynamic.model)
176 robot.rdynamic.setData(robot.rdynamic.model.createData())
177 plug(robot.base_estimator.q, robot.rdynamic.position)
178 robot.rdynamic.velocity.value = [0.0] * robotDim
179 robot.rdynamic.acceleration.value = [0.0] * robotDim
180 
181 # --- CoM Estimation
182 cdc_estimator = DcmEstimator("cdc_estimator")
183 cdc_estimator.init(dt, robot_name)
184 plug(robot.e2q.quaternion, cdc_estimator.q)
185 plug(robot.base_estimator.v, cdc_estimator.v)
186 robot.cdc_estimator = cdc_estimator
187 
188 # --- DCM Estimation
189 estimator = DummyDcmEstimator("dummy")
190 plug(robot.wp.omegaDes, estimator.omega)
191 estimator.mass.value = 1.0
192 plug(robot.cdc_estimator.c, estimator.com)
193 plug(robot.cdc_estimator.dc, estimator.momenta)
194 estimator.init()
195 robot.estimator = estimator
196 
197 # --- Force calibration
198 robot.ftc = create_ft_calibrator(robot, ft_conf)
199 
200 # --- ZMP estimation
201 zmp_estimator = SimpleZmpEstimator("zmpEst")
202 robot.rdynamic.createOpPoint("sole_LF", "left_sole_link")
203 robot.rdynamic.createOpPoint("sole_RF", "right_sole_link")
204 plug(robot.rdynamic.sole_LF, zmp_estimator.poseLeft)
205 plug(robot.rdynamic.sole_RF, zmp_estimator.poseRight)
206 plug(robot.ftc.left_foot_force_out, zmp_estimator.wrenchLeft)
207 plug(robot.ftc.right_foot_force_out, zmp_estimator.wrenchRight)
208 zmp_estimator.init()
209 robot.zmp_estimator = zmp_estimator
210 
211 # -------------------------- ADMITTANCE CONTROL --------------------------
212 
213 # --- DCM controller
214 Kp_dcm = [8.0] * 3
215 Ki_dcm = [0.0, 0.0, 0.0] # zero (to be set later)
216 Kz_dcm = [0.0] * 3
217 gamma_dcm = 0.2
218 
219 dcm_controller = DcmController("dcmCtrl")
220 
221 dcm_controller.Kp.value = Kp_dcm
222 dcm_controller.Ki.value = Ki_dcm
223 dcm_controller.Kz.value = Kz_dcm
224 dcm_controller.decayFactor.value = gamma_dcm
225 dcm_controller.mass.value = mass
226 plug(robot.wp.omegaDes, dcm_controller.omega)
227 
228 plug(robot.cdc_estimator.c, dcm_controller.com)
229 plug(robot.estimator.dcm, dcm_controller.dcm)
230 
231 plug(robot.wp.zmpDes, dcm_controller.zmpDes)
232 plug(robot.wp.dcmDes, dcm_controller.dcmDes)
233 
234 plug(robot.zmp_estimator.zmp, dcm_controller.zmp)
235 
236 dcm_controller.init(dt)
237 
238 robot.dcm_control = dcm_controller
239 
240 Ki_dcm = [1.0, 1.0, 1.0] # this value is employed later
241 
242 Kz_dcm = [0.0, 0.0, 0.0] # this value is employed later
243 
244 # --- CoM admittance controller
245 Kp_adm = [0.0, 0.0, 0.0] # zero (to be set later)
246 
247 com_admittance_control = ComAdmittanceController("comAdmCtrl")
248 com_admittance_control.Kp.value = Kp_adm
249 plug(robot.zmp_estimator.zmp, com_admittance_control.zmp)
250 com_admittance_control.zmpDes.value = (
251  robot.wp.zmpDes.value
252 ) # should be plugged to robot.dcm_control.zmpRef
253 plug(robot.wp.acomDes, com_admittance_control.ddcomDes)
254 
255 com_admittance_control.init(dt)
256 com_admittance_control.setState(robot.wp.comDes.value, [0.0, 0.0, 0.0])
257 
258 robot.com_admittance_control = com_admittance_control
259 
260 Kp_adm = [15.0, 15.0, 0.0] # this value is employed later
261 
262 # --- Control Manager
263 robot.cm = create_ctrl_manager(cm_conf, dt, robot_name="robot")
264 robot.cm.addCtrlMode("sot_input")
265 robot.cm.setCtrlMode("all", "sot_input")
266 robot.cm.addEmergencyStopSIN("zmp")
267 
268 # -------------------------- SOT CONTROL --------------------------
269 
270 # --- Upper body
271 robot.taskUpperBody = Task("task_upper_body")
272 robot.taskUpperBody.feature = FeaturePosture("feature_upper_body")
273 
274 q = list(robot.dynamic.position.value)
275 robot.taskUpperBody.feature.state.value = q
276 robot.taskUpperBody.feature.posture.value = q
277 
278 robotDim = robot.dynamic.getDimension() # 38
279 for i in range(18, robotDim):
280  robot.taskUpperBody.feature.selectDof(i, True)
281 
282 robot.taskUpperBody.controlGain.value = 100.0
283 robot.taskUpperBody.add(robot.taskUpperBody.feature.name)
284 plug(robot.dynamic.position, robot.taskUpperBody.feature.state)
285 
286 # --- CONTACTS
287 # define contactLF and contactRF
288 robot.contactLF = MetaTaskKine6d(
289  "contactLF", robot.dynamic, "LF", robot.OperationalPointsMap["left-ankle"]
290 )
291 robot.contactLF.feature.frame("desired")
292 robot.contactLF.gain.setConstant(300)
293 plug(robot.wp.footLeftDes, robot.contactLF.featureDes.position) # .errorIN?
294 locals()["contactLF"] = robot.contactLF
295 
296 robot.contactRF = MetaTaskKine6d(
297  "contactRF", robot.dynamic, "RF", robot.OperationalPointsMap["right-ankle"]
298 )
299 robot.contactRF.feature.frame("desired")
300 robot.contactRF.gain.setConstant(300)
301 plug(robot.wp.footRightDes, robot.contactRF.featureDes.position) # .errorIN?
302 locals()["contactRF"] = robot.contactRF
303 
304 # --- COM height
305 robot.taskComH = MetaTaskKineCom(robot.dynamic, name="comH")
306 plug(robot.wp.comDes, robot.taskComH.featureDes.errorIN)
307 robot.taskComH.task.controlGain.value = 100.0
308 robot.taskComH.feature.selec.value = "100"
309 
310 # --- COM
311 robot.taskCom = MetaTaskKineCom(robot.dynamic)
312 plug(robot.com_admittance_control.comRef, robot.taskCom.featureDes.errorIN)
313 plug(robot.com_admittance_control.dcomRef, robot.taskCom.featureDes.errordotIN)
314 robot.taskCom.task.controlGain.value = 100.0
315 robot.taskCom.task.setWithDerivative(True)
316 robot.taskCom.feature.selec.value = "011"
317 
318 # --- Waist
319 robot.keepWaist = MetaTaskKine6d(
320  "keepWaist", robot.dynamic, "WT", robot.OperationalPointsMap["waist"]
321 )
322 robot.keepWaist.feature.frame("desired")
323 robot.keepWaist.gain.setConstant(300)
324 plug(robot.wp.waistDes, robot.keepWaist.featureDes.position)
325 robot.keepWaist.feature.selec.value = "111000"
326 locals()["keepWaist"] = robot.keepWaist
327 
328 # --- SOT solver
329 robot.sot = SOT("sot")
330 robot.sot.setSize(robot.dynamic.getDimension())
331 
332 # --- State integrator
333 robot.integrate = SimpleStateIntegrator("integrate")
334 robot.integrate.init(dt)
335 robot.integrate.setState(robot.device.state.value)
336 robot.integrate.setVelocity(robot.dynamic.getDimension() * [0.0])
337 
338 # --- Hip flexibility compensation --------------------------------
339 
341  robot, hipFlexCompConfig, robot_name
342 )
343 plug(robot.phaseInt.sout, robot.hipComp.phase)
344 if not flexi:
345  robot.hipComp.K_l.value = float("inf") # disable
346  robot.hipComp.K_r.value = float("inf") # disable
347 
348 # --- Plug SOT control to device through control manager, state integrator and hip flexibility compensation
349 plug(robot.sot.control, robot.cm.ctrl_sot_input)
350 plug(robot.cm.u_safe, robot.integrate.control)
351 plug(robot.integrate.state, robot.hipComp.q_des)
352 plug(robot.hipComp.q_cmd, robot.device.control)
353 
354 robot.sot.push(robot.taskUpperBody.name)
355 robot.sot.push(robot.contactRF.task.name)
356 robot.sot.push(robot.contactLF.task.name)
357 robot.sot.push(robot.taskComH.task.name)
358 robot.sot.push(robot.taskCom.task.name)
359 robot.sot.push(robot.keepWaist.task.name)
360 # robot.sot.push(robot.taskPos.name)
361 # robot.device.control.recompute(0) # this crashes as it employs joint sensors which are not ready yet
362 
363 # --- Delay
364 robot.delay_pos = DelayVector("delay_pos")
365 robot.delay_pos.setMemory(robot.device.state.value)
366 robot.device.before.addSignal(robot.delay_pos.name + ".current")
367 plug(robot.integrate.state, robot.delay_pos.sin)
368 
369 robot.delay_vel = DelayVector("delay_vel")
370 robot.delay_vel.setMemory(robot.dynamic.getDimension() * [0.0])
371 robot.device.before.addSignal(robot.delay_vel.name + ".current")
372 plug(robot.cm.u_safe, robot.delay_vel.sin)
373 
374 # --- Plug integrator instead of device
375 plug(robot.delay_pos.previous, robot.pselec.sin)
376 plug(robot.pselec.sout, robot.base_estimator.joint_positions)
377 plug(robot.delay_vel.previous, robot.vselec.sin)
378 
379 # --- Fix robot.dynamic inputs
380 plug(robot.delay_pos.previous, robot.dynamic.position)
381 plug(robot.delay_vel.previous, robot.dynamic.velocity)
382 robot.dvdt = Derivator_of_Vector("dv_dt")
383 robot.dvdt.dt.value = dt
384 plug(robot.delay_vel.previous, robot.dvdt.sin)
385 plug(robot.dvdt.sout, robot.dynamic.acceleration)
386 
387 # -------------------------- PLOTS --------------------------
388 
389 # --- ROS PUBLISHER
390 robot.publisher = create_rospublish(robot, "robot_publisher")
391 
392 create_topic(robot.publisher, robot.device, "state", robot=robot, data_type="vector")
394  robot.publisher, robot.base_estimator, "q", robot=robot, data_type="vector"
395 )
396 # create_topic(robot.publisher, robot.stf, 'q', robot = robot, data_type='vector')
397 
399  robot.publisher, robot.comTrajGen, "x", robot=robot, data_type="vector"
400 ) # generated CoM
402  robot.publisher, robot.comTrajGen, "dx", robot=robot, data_type="vector"
403 ) # generated CoM velocity
405  robot.publisher, robot.comTrajGen, "ddx", robot=robot, data_type="vector"
406 ) # generated CoM acceleration
407 
409  robot.publisher, robot.wp, "comDes", robot=robot, data_type="vector"
410 ) # desired CoM
411 
413  robot.publisher, robot.cdc_estimator, "c", robot=robot, data_type="vector"
414 ) # estimated CoM
416  robot.publisher, robot.cdc_estimator, "dc", robot=robot, data_type="vector"
417 ) # estimated CoM velocity
418 
420  robot.publisher,
421  robot.com_admittance_control,
422  "comRef",
423  robot=robot,
424  data_type="vector",
425 ) # reference CoM
427  robot.publisher, robot.dynamic, "com", robot=robot, data_type="vector"
428 ) # resulting SOT CoM
429 
431  robot.publisher, robot.dcm_control, "dcmDes", robot=robot, data_type="vector"
432 ) # desired DCM
434  robot.publisher, robot.estimator, "dcm", robot=robot, data_type="vector"
435 ) # estimated DCM
436 
438  robot.publisher, robot.zmpTrajGen, "x", robot=robot, data_type="vector"
439 ) # generated ZMP
441  robot.publisher, robot.wp, "zmpDes", robot=robot, data_type="vector"
442 ) # desired ZMP
444  robot.publisher, robot.dynamic, "zmp", robot=robot, data_type="vector"
445 ) # SOT ZMP
447  robot.publisher, robot.zmp_estimator, "zmp", robot=robot, data_type="vector"
448 ) # estimated ZMP
450  robot.publisher, robot.dcm_control, "zmpRef", robot=robot, data_type="vector"
451 ) # reference ZMP
452 
453 # create_topic(robot.publisher, robot.device, 'forceLLEG', robot = robot, data_type='vector') # measured left wrench
454 # create_topic(robot.publisher, robot.device, 'forceRLEG', robot = robot, data_type='vector') # measured right wrench
455 
456 # create_topic(robot.publisher, robot.device_filters.ft_LF_filter, 'x_filtered', robot = robot, data_type='vector') # filtered left wrench
457 # create_topic(robot.publisher, robot.device_filters.ft_RF_filter, 'x_filtered', robot = robot, data_type='vector') # filtered right wrench
458 
460  robot.publisher, robot.waistTrajGen, "x", robot=robot, data_type="vector"
461 ) # desired waist orientation
462 
464  robot.publisher, robot.lfTrajGen, "x", robot=robot, data_type="vector"
465 ) # desired left foot pose
467  robot.publisher, robot.rfTrajGen, "x", robot=robot, data_type="vector"
468 ) # desired right foot pose
469 
471  robot.publisher, robot.ftc, "left_foot_force_out", robot=robot, data_type="vector"
472 ) # calibrated left wrench
474  robot.publisher, robot.ftc, "right_foot_force_out", robot=robot, data_type="vector"
475 ) # calibrated right wrench
476 
478  robot.publisher, robot.dynamic, "LF", robot=robot, data_type="matrixHomo"
479 ) # left foot
481  robot.publisher, robot.dynamic, "RF", robot=robot, data_type="matrixHomo"
482 ) # right foot
483 
484 create_topic(robot.publisher, robot.hipComp, "delta_q", robot=robot, data_type="vector")
485 create_topic(robot.publisher, robot.hipComp, "q_cmd", robot=robot, data_type="vector")
486 create_topic(robot.publisher, robot.hipComp, "q_des", robot=robot, data_type="vector")
487 create_topic(robot.publisher, robot.hipComp, "tau", robot=robot, data_type="vector")
489  robot.publisher, robot.hipComp, "tau_filt", robot=robot, data_type="vector"
490 )
491 
492 # --- TRACER
493 robot.tracer = TracerRealTime("com_tracer")
494 robot.tracer.setBufferSize(80 * (2**20))
495 robot.tracer.open("/tmp", "dg_", ".dat")
496 robot.device.after.addSignal("{0}.triger".format(robot.tracer.name))
497 
498 addTrace(robot.tracer, robot.wp, "comDes") # desired CoM
499 
500 addTrace(robot.tracer, robot.cdc_estimator, "c") # estimated CoM
501 # addTrace(robot.tracer, robot.cdc_estimator, 'dc') # estimated CoM velocity
502 
503 addTrace(robot.tracer, robot.com_admittance_control, "comRef") # reference CoM
504 addTrace(robot.tracer, robot.dynamic, "com") # resulting SOT CoM
505 
506 # addTrace(robot.tracer, robot.dcm_control, 'dcmDes') # desired DCM
507 # addTrace(robot.tracer, robot.estimator, 'dcm') # estimated DCM
508 
509 # addTrace(robot.tracer, robot.dcm_control, 'zmpDes') # desired ZMP
510 # addTrace(robot.tracer, robot.dynamic, 'zmp') # SOT ZMP
511 addTrace(robot.tracer, robot.zmp_estimator, "zmp") # estimated ZMP
512 addTrace(robot.tracer, robot.dcm_control, "zmpRef") # reference ZMP
513 
514 # addTrace(robot.tracer, robot.ftc, 'left_foot_force_out') # calibrated left wrench
515 # addTrace(robot.tracer, robot.ftc, 'right_foot_force_out') # calibrated right wrench
516 
517 # addTrace(robot.tracer, robot.dynamic, 'LF') # left foot
518 # addTrace(robot.tracer, robot.dynamic, 'RF') # right foot
519 
520 robot.tracer.start()
sot_talos_balance.create_entities_utils.set_trigger
def set_trigger(robot, on)
Definition: create_entities_utils.py:707
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.addTrace
def addTrace(tracer, entity, signalName)
Definition: create_entities_utils.py:402
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_hip_flexibility_compensation
def create_hip_flexibility_compensation(robot, conf, robot_name="robot")
Definition: create_entities_utils.py:240
dynamicgraph::sot::talos_balance::DelayVector
Delay< Vector, int > DelayVector
Definition: delay.hh:101
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_scalar_trajectory_generator
def create_scalar_trajectory_generator(dt, init_value, name)
Definition: create_entities_utils.py:86
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.load_folder
def load_folder(robot, folder, zmp=False)
Definition: create_entities_utils.py:721
sot_talos_balance.create_entities_utils.create_device_filters
def create_device_filters(robot, dt)
Definition: create_entities_utils.py:279