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