sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
test_dcm_zmp_control.py
Go to the documentation of this file.
1 """Test CoM admittance control as described in paper"""
2 
3 from sys import argv
4 from time import sleep
5 
6 from dynamic_graph.sot_talos_balance.utils.run_test_utils import (
7  ask_for_confirmation,
8  get_file_folder,
9  run_ft_calibration,
10  run_test,
11  runCommandClient,
12 )
13 
14 try:
15  # Python 2
16  input = raw_input # noqa
17 except NameError:
18  pass
19 
20 test_folder, sot_talos_balance_folder = get_file_folder(argv)
21 
22 run_test("appli_dcm_zmp_control.py")
23 
24 run_ft_calibration("robot.ftc")
25 input("Wait before running the test")
26 
27 # Connect ZMP reference and reset controllers
28 print("Connect ZMP reference")
29 runCommandClient("plug(robot.zmp_estimator.emergencyStop,robot.cm.emergencyStop_zmp)")
30 runCommandClient("plug(robot.dcm_control.zmpRef,robot.com_admittance_control.zmpDes)")
32  "robot.com_admittance_control.setState(robot.wp.comDes.value,[0.0,0.0,0.0])"
33 )
34 runCommandClient("robot.com_admittance_control.Kp.value = Kp_adm")
35 runCommandClient("robot.dcm_control.resetDcmIntegralError()")
36 runCommandClient("robot.dcm_control.Ki.value = Ki_dcm")
37 runCommandClient("robot.dcm_control.Kz.value = Kz_dcm")
38 
39 if test_folder is not None:
40  c = ask_for_confirmation("Execute trajectory?")
41  if c:
42  print("Executing the trajectory")
43  runCommandClient("robot.triggerTrajGen.sin.value = 1")
44  else:
45  print("Not executing the trajectory")
46 else:
47  c = ask_for_confirmation("Execute a sinusoid?")
48  if c:
49  print("Putting the robot in position...")
50  runCommandClient("robot.comTrajGen.move(1,-0.025,1.0)")
51  sleep(1.0)
52  print("Robot is in position!")
53 
54  c2 = ask_for_confirmation("Confirm executing the sinusoid?")
55  if c2:
56  print("Executing the sinusoid...")
57  runCommandClient("robot.comTrajGen.startSinusoid(1,0.025,2.0)")
58  print("Sinusoid started!")
59  else:
60  print("Not executing the sinusoid")
61 
62  c3 = ask_for_confirmation("Put the robot back?")
63  if c3:
64  print("Stopping the robot...")
65  runCommandClient("robot.comTrajGen.stop(1)")
66  sleep(5.0)
67  print("Putting the robot back...")
68  runCommandClient("robot.comTrajGen.move(1,0.0,1.0)")
69  sleep(1.0)
70  print("The robot is back in position!")
71  else:
72  print("Not putting the robot back")
73  else:
74  print("Not executing the sinusoid")
75 
76  c = ask_for_confirmation("Raise the foot?")
77  if c:
78  print("Putting the robot in position...")
79  runCommandClient("robot.comTrajGen.move(1,-0.08,10.0)")
80  sleep(10.0)
81  print("Robot is in position!")
82 
83  foot_on_ground = True
84 
85  c2 = ask_for_confirmation("Confirm raising the foot?")
86  if c2:
87  print("Raising the foot...")
88  runCommandClient("h = robot.dynamic.LF.value[2][3]")
89  runCommandClient("robot.lfTrajGen.move(2,h+0.05,10.0)")
90  sleep(10.0)
91  print("Foot has been raised!")
92  foot_on_ground = False
93  c3 = ask_for_confirmation("Put the foot back?")
94  if c3:
95  print("Putting the foot back...")
96  runCommandClient("robot.lfTrajGen.move(2,h,10.0)")
97  sleep(10.0)
98  print("The foot is back in position!")
99  foot_on_ground = True
100  else:
101  print("Not putting the foot back")
102  else:
103  print("Not raising the foot")
104 
105  if foot_on_ground:
106  c4 = ask_for_confirmation("Put the robot back?")
107  if c4:
108  print("Putting the robot back...")
109  runCommandClient("robot.comTrajGen.move(1,0.0,10.0)")
110  sleep(10.0)
111  print("The robot is back in position!")
112  else:
113  print("Not putting the robot back")
114  else:
115  print("Not raising the foot")
116 
117 input("Wait before dumping the data")
118 
119 runCommandClient("dump_tracer(robot.tracer)")
120 
121 print("Bye!")
def run_ft_calibration(sensor_name, force=False)
def run_test(appli, verbosity=1, interactive=True)