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