sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
appli_dcm_zmp_control_distribute.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.distribute_conf as distribute_conf
9 import dynamic_graph.sot_talos_balance.talos.ft_calibration_conf as ft_conf
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 from dynamic_graph.sot_talos_balance.round_double_to_int import RoundDoubleToInt
29 
30 cm_conf.CTRL_MAX = 10.0 # temporary hack
31 
32 robot.timeStep = robot.device.getTimeStep()
33 dt = robot.timeStep
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 robot.triggerTrajGen.sin.value = 0
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 # --- Rho
119 robot.rhoTrajGen = create_scalar_trajectory_generator(dt, 0.5, "rhoTrajGen")
120 robot.rhoTrajGen.x.recompute(0) # trigger computation of initial value
121 robot.rhoScalar = Component_of_vector("rho_scalar")
122 robot.rhoScalar.setIndex(0)
123 plug(robot.rhoTrajGen.x, robot.rhoScalar.sin)
124 plug(robot.triggerTrajGen.sout, robot.rhoTrajGen.trigger)
125 
126 # --- Phase
127 robot.phaseTrajGen = create_scalar_trajectory_generator(dt, 0.0, "phaseTrajGen")
128 robot.phaseTrajGen.x.recompute(0) # trigger computation of initial value
129 robot.phaseScalar = Component_of_vector("phase_scalar")
130 robot.phaseScalar.setIndex(0)
131 plug(robot.phaseTrajGen.x, robot.phaseScalar.sin)
132 robot.phaseInt = RoundDoubleToInt("phase_int")
133 plug(robot.phaseScalar.sout, robot.phaseInt.sin)
134 plug(robot.triggerTrajGen.sout, robot.phaseTrajGen.trigger)
135 
136 # --- Load files
137 if folder is not None:
138  robot.comTrajGen.playTrajectoryFile(folder + "CoM.dat")
139  robot.lfTrajGen.playTrajectoryFile(folder + "LeftFoot.dat")
140  robot.rfTrajGen.playTrajectoryFile(folder + "RightFoot.dat")
141  # robot.zmpTrajGen.playTrajectoryFile(folder + 'ZMP.dat')
142  robot.waistTrajGen.playTrajectoryFile(folder + "WaistOrientation.dat")
143  robot.rhoTrajGen.playTrajectoryFile(folder + "Rho.dat")
144  robot.phaseTrajGen.playTrajectoryFile(folder + "Phase.dat")
145 
146 # --- Interface with controller entities
147 
148 wp = DummyWalkingPatternGenerator("dummy_wp")
149 wp.init()
150 wp.omega.value = omega
151 plug(robot.rhoScalar.sout, wp.rho)
152 plug(robot.phaseInt.sout, wp.phase)
153 plug(robot.waistToMatrix.sout, wp.waist)
154 plug(robot.lfToMatrix.sout, wp.footLeft)
155 plug(robot.rfToMatrix.sout, wp.footRight)
156 plug(robot.comTrajGen.x, wp.com)
157 plug(robot.comTrajGen.dx, wp.vcom)
158 plug(robot.comTrajGen.ddx, wp.acom)
159 # if folder is not None:
160 # plug(robot.zmpTrajGen.x, wp.zmp)
161 
162 robot.wp = wp
163 
164 # --- Compute the values to use them in initialization
165 robot.wp.comDes.recompute(0)
166 robot.wp.dcmDes.recompute(0)
167 robot.wp.zmpDes.recompute(0)
168 
169 # -------------------------- ESTIMATION --------------------------
170 
171 # --- Base Estimation
172 robot.device_filters = create_device_filters(robot, dt)
173 robot.imu_filters = create_imu_filters(robot, dt)
174 robot.base_estimator = create_base_estimator(robot, dt, base_estimator_conf)
175 
176 robot.m2qLF = MatrixHomoToPoseQuaternion("m2qLF")
177 plug(robot.dynamic.LF, robot.m2qLF.sin)
178 plug(robot.m2qLF.sout, robot.base_estimator.lf_ref_xyzquat)
179 robot.m2qRF = MatrixHomoToPoseQuaternion("m2qRF")
180 plug(robot.dynamic.RF, robot.m2qRF.sin)
181 plug(robot.m2qRF.sout, robot.base_estimator.rf_ref_xyzquat)
182 
183 # robot.be_filters = create_be_filters(robot, dt)
184 
185 # --- Conversion
186 e2q = EulerToQuat("e2q")
187 plug(robot.base_estimator.q, e2q.euler)
188 robot.e2q = e2q
189 
190 # --- Kinematic computations
191 robot.rdynamic = DynamicPinocchio("real_dynamics")
192 robot.rdynamic.setModel(robot.dynamic.model)
193 robot.rdynamic.setData(robot.rdynamic.model.createData())
194 plug(robot.base_estimator.q, robot.rdynamic.position)
195 robot.rdynamic.velocity.value = [0.0] * robotDim
196 robot.rdynamic.acceleration.value = [0.0] * robotDim
197 
198 # --- CoM Estimation
199 cdc_estimator = DcmEstimator("cdc_estimator")
200 cdc_estimator.init(dt, robot_name)
201 plug(robot.e2q.quaternion, cdc_estimator.q)
202 plug(robot.base_estimator.v, cdc_estimator.v)
203 robot.cdc_estimator = cdc_estimator
204 
205 # --- DCM Estimation
206 estimator = DummyDcmEstimator("dummy")
207 plug(robot.wp.omegaDes, estimator.omega)
208 estimator.mass.value = 1.0
209 plug(robot.cdc_estimator.c, estimator.com)
210 plug(robot.cdc_estimator.dc, estimator.momenta)
211 estimator.init()
212 robot.estimator = estimator
213 
214 # --- Force calibration
215 robot.ftc = create_ft_calibrator(robot, ft_conf)
216 
217 # --- ZMP estimation
218 zmp_estimator = SimpleZmpEstimator("zmpEst")
219 robot.rdynamic.createOpPoint("sole_LF", "left_sole_link")
220 robot.rdynamic.createOpPoint("sole_RF", "right_sole_link")
221 plug(robot.rdynamic.sole_LF, zmp_estimator.poseLeft)
222 plug(robot.rdynamic.sole_RF, zmp_estimator.poseRight)
223 plug(robot.ftc.left_foot_force_out, zmp_estimator.wrenchLeft)
224 plug(robot.ftc.right_foot_force_out, zmp_estimator.wrenchRight)
225 zmp_estimator.init()
226 robot.zmp_estimator = zmp_estimator
227 
228 # -------------------------- ADMITTANCE CONTROL --------------------------
229 
230 # --- DCM controller
231 Kp_dcm = [8.0] * 3
232 Ki_dcm = [0.0, 0.0, 0.0] # zero (to be set later)
233 Kz_dcm = [0.0] * 3
234 gamma_dcm = 0.2
235 
236 dcm_controller = DcmController("dcmCtrl")
237 
238 dcm_controller.Kp.value = Kp_dcm
239 dcm_controller.Ki.value = Ki_dcm
240 dcm_controller.Kz.value = Kz_dcm
241 dcm_controller.decayFactor.value = gamma_dcm
242 dcm_controller.mass.value = mass
243 plug(robot.wp.omegaDes, dcm_controller.omega)
244 
245 plug(robot.cdc_estimator.c, dcm_controller.com)
246 plug(robot.estimator.dcm, dcm_controller.dcm)
247 
248 plug(robot.wp.zmpDes, dcm_controller.zmpDes)
249 plug(robot.wp.dcmDes, dcm_controller.dcmDes)
250 
251 plug(robot.zmp_estimator.zmp, dcm_controller.zmp)
252 
253 dcm_controller.init(dt)
254 
255 robot.dcm_control = dcm_controller
256 
257 Ki_dcm = [1.0, 1.0, 1.0] # this value is employed later
258 
259 Kz_dcm = [0.0, 0.0, 0.0] # this value is employed later
260 
261 # --- Distribute wrench
262 distribute = create_distribute_wrench(distribute_conf)
263 plug(robot.e2q.quaternion, distribute.q)
264 plug(robot.dcm_control.wrenchRef, distribute.wrenchDes)
265 plug(robot.wp.rhoDes, distribute.rho)
266 plug(robot.wp.phaseDes, distribute.phase)
267 distribute.init(robot_name)
268 robot.distribute = distribute
269 
270 # --- CoM admittance controller
271 Kp_adm = [0.0, 0.0, 0.0] # zero (to be set later)
272 
273 com_admittance_control = ComAdmittanceController("comAdmCtrl")
274 com_admittance_control.Kp.value = Kp_adm
275 plug(robot.zmp_estimator.zmp, com_admittance_control.zmp)
276 com_admittance_control.zmpDes.value = (
277  robot.wp.zmpDes.value
278 ) # should be plugged to robot.distribute.zmpRef
279 plug(robot.wp.acomDes, com_admittance_control.ddcomDes)
280 
281 com_admittance_control.init(dt)
282 com_admittance_control.setState(robot.wp.comDes.value, [0.0, 0.0, 0.0])
283 
284 robot.com_admittance_control = com_admittance_control
285 
286 Kp_adm = [15.0, 15.0, 0.0] # this value is employed later
287 
288 # --- Control Manager
289 robot.cm = create_ctrl_manager(cm_conf, dt, robot_name="robot")
290 robot.cm.addCtrlMode("sot_input")
291 robot.cm.setCtrlMode("all", "sot_input")
292 robot.cm.addEmergencyStopSIN("zmp")
293 robot.cm.addEmergencyStopSIN("distribute")
294 
295 # -------------------------- SOT CONTROL --------------------------
296 
297 # --- Upper body
298 robot.taskUpperBody = Task("task_upper_body")
299 robot.taskUpperBody.feature = FeaturePosture("feature_upper_body")
300 
301 q = list(robot.dynamic.position.value)
302 robot.taskUpperBody.feature.state.value = q
303 robot.taskUpperBody.feature.posture.value = q
304 
305 robotDim = robot.dynamic.getDimension() # 38
306 for i in range(18, robotDim):
307  robot.taskUpperBody.feature.selectDof(i, True)
308 
309 robot.taskUpperBody.controlGain.value = 100.0
310 robot.taskUpperBody.add(robot.taskUpperBody.feature.name)
311 plug(robot.dynamic.position, robot.taskUpperBody.feature.state)
312 
313 # --- CONTACTS
314 # define contactLF and contactRF
315 robot.contactLF = MetaTaskKine6d(
316  "contactLF", robot.dynamic, "LF", robot.OperationalPointsMap["left-ankle"]
317 )
318 robot.contactLF.feature.frame("desired")
319 robot.contactLF.gain.setConstant(300)
320 plug(robot.wp.footLeftDes, robot.contactLF.featureDes.position) # .errorIN?
321 locals()["contactLF"] = robot.contactLF
322 
323 robot.contactRF = MetaTaskKine6d(
324  "contactRF", robot.dynamic, "RF", robot.OperationalPointsMap["right-ankle"]
325 )
326 robot.contactRF.feature.frame("desired")
327 robot.contactRF.gain.setConstant(300)
328 plug(robot.wp.footRightDes, robot.contactRF.featureDes.position) # .errorIN?
329 locals()["contactRF"] = robot.contactRF
330 
331 # --- COM height
332 robot.taskComH = MetaTaskKineCom(robot.dynamic, name="comH")
333 plug(robot.wp.comDes, robot.taskComH.featureDes.errorIN)
334 robot.taskComH.task.controlGain.value = 100.0
335 robot.taskComH.feature.selec.value = "100"
336 
337 # --- COM
338 robot.taskCom = MetaTaskKineCom(robot.dynamic)
339 plug(robot.com_admittance_control.comRef, robot.taskCom.featureDes.errorIN)
340 plug(robot.com_admittance_control.dcomRef, robot.taskCom.featureDes.errordotIN)
341 robot.taskCom.task.controlGain.value = 100.0
342 robot.taskCom.task.setWithDerivative(True)
343 robot.taskCom.feature.selec.value = "011"
344 
345 # --- Waist
346 robot.keepWaist = MetaTaskKine6d(
347  "keepWaist", robot.dynamic, "WT", robot.OperationalPointsMap["waist"]
348 )
349 robot.keepWaist.feature.frame("desired")
350 robot.keepWaist.gain.setConstant(300)
351 plug(robot.wp.waistDes, robot.keepWaist.featureDes.position)
352 robot.keepWaist.feature.selec.value = "111000"
353 locals()["keepWaist"] = robot.keepWaist
354 
355 # --- SOT solver
356 robot.sot = SOT("sot")
357 robot.sot.setSize(robot.dynamic.getDimension())
358 
359 # --- Plug SOT control to device through control manager
360 plug(robot.sot.control, robot.cm.ctrl_sot_input)
361 plug(robot.cm.u_safe, robot.device.control)
362 
363 robot.sot.push(robot.taskUpperBody.name)
364 robot.sot.push(robot.contactRF.task.name)
365 robot.sot.push(robot.contactLF.task.name)
366 robot.sot.push(robot.taskComH.task.name)
367 robot.sot.push(robot.taskCom.task.name)
368 robot.sot.push(robot.keepWaist.task.name)
369 # robot.sot.push(robot.taskPos.name)
370 # robot.device.control.recompute(0) # this crashes as it employs joint sensors which are not ready yet
371 
372 # --- Fix robot.dynamic inputs
373 plug(robot.device.velocity, robot.dynamic.velocity)
374 robot.dvdt = Derivator_of_Vector("dv_dt")
375 robot.dvdt.dt.value = dt
376 plug(robot.device.velocity, robot.dvdt.sin)
377 plug(robot.dvdt.sout, robot.dynamic.acceleration)
378 
379 # -------------------------- PLOTS --------------------------
380 
381 # --- ROS PUBLISHER
382 robot.publisher = create_rospublish(robot, "robot_publisher")
383 
384 create_topic(robot.publisher, robot.device, "state", robot=robot, data_type="vector")
386  robot.publisher, robot.base_estimator, "q", robot=robot, data_type="vector"
387 )
388 # create_topic(robot.publisher, robot.stf, 'q', robot = robot, data_type='vector')
389 
391  robot.publisher, robot.comTrajGen, "x", robot=robot, data_type="vector"
392 ) # generated CoM
394  robot.publisher, robot.comTrajGen, "dx", robot=robot, data_type="vector"
395 ) # generated CoM velocity
397  robot.publisher, robot.comTrajGen, "ddx", robot=robot, data_type="vector"
398 ) # generated CoM acceleration
399 
401  robot.publisher, robot.wp, "comDes", robot=robot, data_type="vector"
402 ) # desired CoM
403 
405  robot.publisher, robot.cdc_estimator, "c", robot=robot, data_type="vector"
406 ) # estimated CoM
408  robot.publisher, robot.cdc_estimator, "dc", robot=robot, data_type="vector"
409 ) # estimated CoM velocity
410 
412  robot.publisher,
413  robot.com_admittance_control,
414  "comRef",
415  robot=robot,
416  data_type="vector",
417 ) # reference CoM
419  robot.publisher, robot.dynamic, "com", robot=robot, data_type="vector"
420 ) # resulting SOT CoM
421 
423  robot.publisher, robot.dcm_control, "dcmDes", robot=robot, data_type="vector"
424 ) # desired DCM
426  robot.publisher, robot.estimator, "dcm", robot=robot, data_type="vector"
427 ) # estimated DCM
428 
430  robot.publisher, robot.dcm_control, "zmpDes", robot=robot, data_type="vector"
431 ) # desired ZMP
433  robot.publisher, robot.dynamic, "zmp", robot=robot, data_type="vector"
434 ) # SOT ZMP
436  robot.publisher, robot.zmp_estimator, "zmp", robot=robot, data_type="vector"
437 ) # estimated ZMP
439  robot.publisher, robot.dcm_control, "zmpRef", robot=robot, data_type="vector"
440 ) # reference ZMP
441 
443  robot.publisher, robot.dcm_control, "wrenchRef", robot=robot, data_type="vector"
444 ) # unoptimized reference wrench
446  robot.publisher, robot.distribute, "wrenchLeft", robot=robot, data_type="vector"
447 ) # reference left wrench
449  robot.publisher, robot.distribute, "wrenchRight", robot=robot, data_type="vector"
450 ) # reference right wrench
452  robot.publisher, robot.distribute, "wrenchRef", robot=robot, data_type="vector"
453 ) # optimized reference wrench
454 
455 # create_topic(robot.publisher, robot.device, 'forceLLEG', robot = robot, data_type='vector') # measured left wrench
456 # create_topic(robot.publisher, robot.device, 'forceRLEG', robot = robot, data_type='vector') # measured right wrench
457 
458 # create_topic(robot.publisher, robot.device_filters.ft_LF_filter, 'x_filtered', robot = robot, data_type='vector') # filtered left wrench
459 # create_topic(robot.publisher, robot.device_filters.ft_RF_filter, 'x_filtered', robot = robot, data_type='vector') # filtered right wrench
460 
462  robot.publisher, robot.waistTrajGen, "x", robot=robot, data_type="vector"
463 ) # desired waist orientation
464 
466  robot.publisher, robot.lfTrajGen, "x", robot=robot, data_type="vector"
467 ) # desired left foot pose
469  robot.publisher, robot.rfTrajGen, "x", robot=robot, data_type="vector"
470 ) # desired right foot pose
471 
473  robot.publisher, robot.ftc, "left_foot_force_out", robot=robot, data_type="vector"
474 ) # calibrated left wrench
476  robot.publisher, robot.ftc, "right_foot_force_out", robot=robot, data_type="vector"
477 ) # calibrated right wrench
478 
480  robot.publisher, robot.dynamic, "LF", robot=robot, data_type="matrixHomo"
481 ) # left foot
483  robot.publisher, robot.dynamic, "RF", robot=robot, data_type="matrixHomo"
484 ) # right foot
485 
486 
491 
492 # addTrace(robot.tracer, robot.wp, 'comDes') # desired CoM
493 
494 # addTrace(robot.tracer, robot.cdc_estimator, 'c') # estimated CoM
495 # addTrace(robot.tracer, robot.cdc_estimator, 'dc') # estimated CoM velocity
496 
497 # addTrace(robot.tracer, robot.com_admittance_control, 'comRef') # reference CoM
498 # addTrace(robot.tracer, robot.dynamic, 'com') # resulting SOT CoM
499 
500 # addTrace(robot.tracer, robot.dcm_control, 'dcmDes') # desired DCM
501 # addTrace(robot.tracer, robot.estimator, 'dcm') # estimated DCM
502 
503 # addTrace(robot.tracer, robot.dcm_control, 'zmpDes') # desired ZMP
504 # addTrace(robot.tracer, robot.dynamic, 'zmp') # SOT ZMP
505 # addTrace(robot.tracer, robot.zmp_estimator, 'zmp') # estimated ZMP
506 # addTrace(robot.tracer, robot.dcm_control, 'zmpRef') # reference ZMP
507 
508 # addTrace(robot.tracer, robot.dcm_control, 'wrenchRef') # unoptimized reference wrench
509 # addTrace(robot.tracer, robot.distribute, 'wrenchLeft') # reference left wrench
510 # addTrace(robot.tracer, robot.distribute, 'wrenchRight') # reference right wrench
511 # addTrace(robot.tracer, robot.distribute, 'wrenchRef') # optimized reference wrench
512 
513 # addTrace(robot.tracer, robot.ftc, 'left_foot_force_out') # calibrated left wrench
514 # addTrace(robot.tracer, robot.ftc, 'right_foot_force_out') # calibrated right wrench
515 
516 # addTrace(robot.tracer, robot.dynamic, 'LF') # left foot
517 # addTrace(robot.tracer, robot.dynamic, 'RF') # right foot
518 
519 # robot.tracer.start()
sot_talos_balance.create_entities_utils.create_distribute_wrench
def create_distribute_wrench(conf)
Definition: create_entities_utils.py:640
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_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.create_device_filters
def create_device_filters(robot, dt)
Definition: create_entities_utils.py:279