Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Stack Of Tasks
talos_integration_tests
Commits
2caa0f0e
Commit
2caa0f0e
authored
May 29, 2020
by
Guilhem Saurel
Browse files
[Lint] flake8
Among other things, fix syntax for Python 3 compatibility
parent
d26f4fb8
Changes
9
Hide whitespace changes
Inline
Side-by-side
scripts/start_sot_online_walking.py
View file @
2caa0f0e
...
...
@@ -2,16 +2,14 @@
# O. Stasse 17/01/2020
# LAAS, CNRS
import
os
import
rospy
import
math
import
time
import
roslaunch
import
rospkg
import
unittest
import
math
from
gazebo_msgs.srv
import
*
import
roslaunch
import
rospkg
import
rospy
from
gazebo_msgs.srv
import
GetModelState
from
std_srvs.srv
import
Empty
PKG_NAME
=
'talos_integration_tests'
...
...
@@ -58,11 +56,9 @@ class TestSoTTalos(unittest.TestCase):
talos_data_path
+
'/launch/talos_gazebo_alone.launch'
,
'world:=empty_forced'
,
'enable_leg_passive:=false'
]
roslaunch_args
=
cli_args
[
1
:]
roslaunch_file
=
[(
roslaunch
.
rlutil
.
resolve_launch_arguments
\
(
cli_args
)[
0
],
roslaunch_args
)]
roslaunch_file
=
[(
roslaunch
.
rlutil
.
resolve_launch_arguments
(
cli_args
)[
0
],
roslaunch_args
)]
launch_gazebo_alone
=
roslaunch
.
parent
.
\
ROSLaunchParent
(
uuid
,
roslaunch_file
)
launch_gazebo_alone
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
roslaunch_file
)
launch_gazebo_alone
.
start
()
rospy
.
loginfo
(
"talos_gazebo_alone started"
)
...
...
@@ -72,31 +68,28 @@ class TestSoTTalos(unittest.TestCase):
time
.
sleep
(
5
)
# Spawn talos model in gazebo
launch_gazebo_spawn_hs
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
talos_data_path
+
'/launch/talos_gazebo_spawn_hs.launch'
])
#launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
launch_gazebo_spawn_hs
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
talos_data_path
+
'/launch/talos_gazebo_spawn_hs.launch'
])
#
launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
# [ros_data_path+'/launch/talos_gazebo_spawn_hs_wide.launch'])
launch_gazebo_spawn_hs
.
start
()
rospy
.
loginfo
(
"talos_gazebo_spawn_hs started"
)
rospy
.
wait_for_service
(
"/gains/arm_left_1_joint/set_parameters"
)
time
.
sleep
(
5
)
gazebo_unpause_physics
=
rospy
.
\
ServiceProxy
(
'/gazebo/unpause_physics'
,
Empty
)
gazebo_unpause_physics
=
rospy
.
ServiceProxy
(
'/gazebo/unpause_physics'
,
Empty
)
gazebo_unpause_physics
()
# Start roscontrol
launch_bringup
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
talos_data_path
+
'/launch/talos_bringup.launch'
])
launch_bringup
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
talos_data_path
+
'/launch/talos_bringup.launch'
])
launch_bringup
.
start
()
rospy
.
loginfo
(
"talos_bringup started"
)
# Start sot
roscontrol_sot_talos_path
=
arospack
.
get_path
(
'roscontrol_sot_talos'
)
launch_roscontrol_sot_talos
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
roscontrol_sot_talos_path
+
\
'/launch/sot_talos_controller_gazebo.launch'
])
launch_roscontrol_sot_talos
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
roscontrol_sot_talos_path
+
'/launch/sot_talos_controller_gazebo.launch'
])
launch_roscontrol_sot_talos
.
start
()
rospy
.
loginfo
(
"roscontrol_sot_talos started"
)
...
...
@@ -104,14 +97,12 @@ class TestSoTTalos(unittest.TestCase):
pkg_name
=
'talos_integration_tests'
executable
=
'test_online_walking.py'
node_name
=
'test_online_walking_py'
test_sot_online_walking_node
=
roslaunch
.
core
.
\
Node
(
pkg_name
,
executable
,
name
=
node_name
)
test_sot_online_walking_node
=
roslaunch
.
core
.
Node
(
pkg_name
,
executable
,
name
=
node_name
)
launch_test_sot_online_walking
=
roslaunch
.
scriptapi
.
ROSLaunch
()
launch_test_sot_online_walking
.
start
()
test_sot_online_walking_process
=
launch_test_sot_online_walking
.
\
launch
(
test_sot_online_walking_node
)
test_sot_online_walking_process
=
launch_test_sot_online_walking
.
launch
(
test_sot_online_walking_node
)
r
=
rospy
.
Rate
(
10
)
while
not
rospy
.
is_shutdown
():
...
...
scripts/start_sot_talos_balance.py
View file @
2caa0f0e
...
...
@@ -2,16 +2,14 @@
# O. Stasse 17/01/2020
# LAAS, CNRS
import
os
import
rospy
import
math
import
time
import
roslaunch
import
rospkg
import
unittest
import
math
from
gazebo_msgs.srv
import
*
import
roslaunch
import
rospkg
import
rospy
from
gazebo_msgs.srv
import
GetModelState
from
std_srvs.srv
import
Empty
PKG_NAME
=
'talos_integration_tests'
...
...
@@ -67,31 +65,28 @@ class TestSoTTalos(unittest.TestCase):
time
.
sleep
(
5
)
# Spawn talos model in gazebo
launch_gazebo_spawn_hs
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
talos_data_path
+
'/launch/talos_gazebo_spawn_hs.launch'
])
#launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
launch_gazebo_spawn_hs
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
talos_data_path
+
'/launch/talos_gazebo_spawn_hs.launch'
])
#
launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
# [ros_data_path+'/launch/talos_gazebo_spawn_hs_wide.launch'])
launch_gazebo_spawn_hs
.
start
()
rospy
.
loginfo
(
"talos_gazebo_spawn_hs started"
)
rospy
.
wait_for_service
(
"/gains/arm_left_1_joint/set_parameters"
)
time
.
sleep
(
5
)
gazebo_unpause_physics
=
rospy
.
\
ServiceProxy
(
'/gazebo/unpause_physics'
,
Empty
)
gazebo_unpause_physics
=
rospy
.
ServiceProxy
(
'/gazebo/unpause_physics'
,
Empty
)
gazebo_unpause_physics
()
# Start roscontrol
launch_bringup
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
talos_data_path
+
'/launch/talos_bringup.launch'
])
launch_bringup
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
talos_data_path
+
'/launch/talos_bringup.launch'
])
launch_bringup
.
start
()
rospy
.
loginfo
(
"talos_bringup started"
)
# Start sot
roscontrol_sot_talos_path
=
arospack
.
get_path
(
'roscontrol_sot_talos'
)
launch_roscontrol_sot_talos
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
roscontrol_sot_talos_path
+
\
'/launch/sot_talos_controller_gazebo.launch'
])
launch_roscontrol_sot_talos
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
roscontrol_sot_talos_path
+
'/launch/sot_talos_controller_gazebo.launch'
])
launch_roscontrol_sot_talos
.
start
()
rospy
.
loginfo
(
"roscontrol_sot_talos started"
)
...
...
@@ -99,14 +94,12 @@ class TestSoTTalos(unittest.TestCase):
pkg_name
=
'talos_integration_tests'
executable
=
'test_sot_talos_balance.py'
node_name
=
'test_sot_talos_balance_py'
test_sot_talos_balance_node
=
roslaunch
.
core
.
\
Node
(
pkg_name
,
executable
,
name
=
node_name
)
test_sot_talos_balance_node
=
roslaunch
.
core
.
Node
(
pkg_name
,
executable
,
name
=
node_name
)
launch_test_sot_talos_balance
=
roslaunch
.
scriptapi
.
ROSLaunch
()
launch_test_sot_talos_balance
.
start
()
test_sot_talos_balance_process
=
launch_test_sot_talos_balance
.
\
launch
(
test_sot_talos_balance_node
)
test_sot_talos_balance_process
=
launch_test_sot_talos_balance
.
launch
(
test_sot_talos_balance_node
)
r
=
rospy
.
Rate
(
10
)
while
not
rospy
.
is_shutdown
():
...
...
scripts/start_talos_gazebo.py
View file @
2caa0f0e
...
...
@@ -2,16 +2,14 @@
# O. Stasse 17/01/2020
# LAAS, CNRS
import
os
import
rospy
import
subprocess
import
time
import
roslaunch
import
rospkg
import
rospy
from
std_srvs.srv
import
Empty
# Start roscore
import
subprocess
roscore
=
subprocess
.
Popen
(
'roscore'
)
time
.
sleep
(
1
)
...
...
@@ -40,7 +38,7 @@ time.sleep(5)
# Spawn talos model in gazebo
launch_gazebo_spawn_hs
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
talos_data_path
+
'/launch/talos_gazebo_spawn_hs.launch'
])
#launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
#
launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
# [talos_data_path+'/launch/talos_gazebo_spawn_hs_wide.launch'])
launch_gazebo_spawn_hs
.
start
()
rospy
.
loginfo
(
"talos_gazebo_spawn_hs started"
)
...
...
scripts/start_talos_gazebo_kine.py
View file @
2caa0f0e
...
...
@@ -2,16 +2,14 @@
# O. Stasse 17/01/2020
# LAAS, CNRS
import
os
import
rospy
import
math
import
time
import
roslaunch
import
rospkg
import
unittest
import
math
from
gazebo_msgs.srv
import
*
import
roslaunch
import
rospkg
import
rospy
from
gazebo_msgs.srv
import
GetLinkState
from
std_srvs.srv
import
Empty
PKG_NAME
=
'talos_integration_tests'
...
...
@@ -70,30 +68,27 @@ class TestSoTTalos(unittest.TestCase):
time
.
sleep
(
5
)
# Spawn talos model in gazebo
launch_gazebo_spawn_hs
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
talos_data_path
+
'/launch/talos_gazebo_spawn_hs.launch'
])
#launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
launch_gazebo_spawn_hs
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
talos_data_path
+
'/launch/talos_gazebo_spawn_hs.launch'
])
#
launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
# [talos_data_path+'/launch/talos_gazebo_spawn_hs_wide.launch'])
launch_gazebo_spawn_hs
.
start
()
rospy
.
loginfo
(
"talos_gazebo_spawn_hs started"
)
rospy
.
wait_for_service
(
"/gains/arm_left_1_joint/set_parameters"
)
time
.
sleep
(
5
)
gazebo_unpause_physics
=
\
rospy
.
ServiceProxy
(
'/gazebo/unpause_physics'
,
Empty
)
gazebo_unpause_physics
=
rospy
.
ServiceProxy
(
'/gazebo/unpause_physics'
,
Empty
)
gazebo_unpause_physics
()
# Start roscontrol
launch_bringup
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
talos_data_path
+
'/launch/talos_bringup.launch'
])
launch_bringup
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
talos_data_path
+
'/launch/talos_bringup.launch'
])
launch_bringup
.
start
()
rospy
.
loginfo
(
"talos_bringup started"
)
# Start sot
roscontrol_sot_talos_path
=
arospack
.
get_path
(
'roscontrol_sot_talos'
)
launch_roscontrol_sot_talos
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
\
[
roscontrol_sot_talos_path
+
\
'/launch/sot_talos_controller_gazebo.launch'
])
launch_roscontrol_sot_talos
=
roslaunch
.
parent
.
ROSLaunchParent
(
uuid
,
[
roscontrol_sot_talos_path
+
'/launch/sot_talos_controller_gazebo.launch'
])
launch_roscontrol_sot_talos
.
start
()
rospy
.
loginfo
(
"roscontrol_sot_talos started"
)
...
...
scripts/test_appli_seq_play.py
View file @
2caa0f0e
#!/usr/bin/python
import
sys
import
rospy
from
dynamic_graph_bridge_msgs.srv
import
RunCommand
from
std_srvs.srv
import
Empty
from
std_srvs.srv
import
*
from
dynamic_graph_bridge_msgs.srv
import
*
try
:
# Python 2
input
=
raw_input
except
NameError
:
pass
def
launchScript
(
code
,
title
,
description
=
""
):
raw_
input
(
title
+
': '
+
description
)
input
(
title
+
': '
+
description
)
rospy
.
loginfo
(
title
)
rospy
.
loginfo
(
code
)
for
line
in
code
:
if
line
!=
''
and
line
[
0
]
!=
'#'
:
print
line
if
line
and
not
line
.
strip
().
startswith
(
'#'
)
:
print
(
line
)
answer
=
runCommandClient
(
str
(
line
))
rospy
.
logdebug
(
answer
)
print
answer
print
(
answer
)
rospy
.
loginfo
(
"...done with "
+
title
)
...
...
@@ -37,11 +42,11 @@ try:
rospy
.
loginfo
(
"Stack of Tasks launched"
)
launchScript
(
initCode
,
'initialize SoT'
)
raw_
input
(
"Wait before starting the dynamic graph"
)
input
(
"Wait before starting the dynamic graph"
)
runCommandStartDynamicGraph
()
raw_
input
(
"Wait before starting the seqplay"
)
input
(
"Wait before starting the seqplay"
)
runCommandClient
(
"aSimpleSeqPlay.start()"
)
except
rospy
.
ServiceException
,
e
:
except
rospy
.
ServiceException
as
e
:
rospy
.
logerr
(
"Service call failed: %s"
%
e
)
scripts/test_kine.py
View file @
2caa0f0e
#! /usr/bin/env python
import
sys
import
rospy
import
time
from
os.path
import
abspath
,
dirname
,
join
from
std_srvs.srv
import
*
from
dynamic_graph_bridge_msgs.srv
import
*
import
rospy
from
dynamic_graph_bridge_msgs.srv
import
RunCommand
from
std_srvs.srv
import
Empty
runCommandClient
=
rospy
.
ServiceProxy
(
'run_command'
,
RunCommand
)
from
sot_talos_balance.utils.run_test_utils
import
runCommandClient
def
handleRunCommandClient
(
code
):
out
=
runCommandClient
(
code
)
...
...
@@ -60,7 +57,7 @@ def runTest():
time
.
sleep
(
10
)
except
rospy
.
ServiceException
,
e
:
except
rospy
.
ServiceException
as
e
:
rospy
.
logerr
(
"Service call failed: %s"
%
e
)
...
...
scripts/test_online_walking.py
View file @
2caa0f0e
#! /usr/bin/env python
import
sys
import
rospy
import
rospkg
import
time
import
unittest
import
math
from
std_srvs.srv
import
*
from
dynamic_graph_bridge_msgs.srv
import
*
from
gazebo_msg
s.srv
import
*
import
rospkg
import
rospy
from
sot_talos_balance.utils.run_test_utils
import
runCommandClient
from
std_srv
s.srv
import
Empty
def
handleRunCommandClient
(
code
):
...
...
@@ -23,12 +19,6 @@ def handleRunCommandClient(code):
PKG_NAME
=
'talos_integration_tests'
'''Test online walking pattern generator'''
from
sys
import
argv
from
sot_talos_balance.utils.run_test_utils
import
\
run_ft_calibration
,
run_test
,
runCommandClient
from
time
import
sleep
def
wait_for_dynamic_graph
():
try
:
...
...
@@ -51,8 +41,7 @@ rospack = rospkg.RosPack()
lpath
=
rospack
.
get_path
(
PKG_NAME
)
print
(
lpath
)
appli_file_name
=
lpath
+
'/../../lib/'
+
PKG_NAME
+
\
'/appli_online_walking.py'
appli_file_name
=
lpath
+
'/../../lib/'
+
PKG_NAME
+
'/appli_online_walking.py'
runCommandStartDynamicGraph
=
rospy
.
ServiceProxy
(
'start_dynamic_graph'
,
Empty
)
rospy
.
loginfo
(
"Stack of Tasks launched"
)
...
...
@@ -68,7 +57,7 @@ runCommandStartDynamicGraph()
rospy
.
loginfo
(
"Stack of Tasks launched"
)
#run_test(appli_file_name, verbosity=1,interactive=False)
#
run_test(appli_file_name, verbosity=1,interactive=False)
time
.
sleep
(
5
)
# Connect ZMP reference and reset controllers
...
...
scripts/test_sot_talos_balance.py
View file @
2caa0f0e
#! /usr/bin/env python
import
sys
import
rospy
import
time
import
unittest
import
math
from
os.path
import
abspath
,
dirname
,
join
from
std_srvs.srv
import
*
from
dynamic_graph_bridge_msgs.srv
import
*
import
rospy
from
sot_talos_balance.utils.run_test_utils
import
runCommandClient
from
std_srvs.srv
import
Empty
def
handleRunCommandClient
(
code
):
...
...
@@ -20,8 +18,6 @@ def handleRunCommandClient(code):
PKG_NAME
=
'talos_integration_tests'
'''Test CoM admittance control as described in paper, with pre-loaded movements'''
from
sot_talos_balance.utils.run_test_utils
import
\
run_ft_calibration
,
run_test
,
runCommandClient
# get the file path for rospy_tutorials
appli_file_name
=
join
(
dirname
(
abspath
(
__file__
)),
'appli_dcmZmpControl_file.py'
)
...
...
src/talos_integration_tests/appli.py
View file @
2caa0f0e
from
dynamic_graph.sot.core.meta_tasks_kine
import
MetaTaskKine6d
,
MetaTaskKineCom
,
gotoNd
from
dynamic_graph.sot.core.matrix_util
import
matrixToTuple
from
dynamic_graph.sot.core.meta_tasks_kine
import
(
MetaTaskKine6d
,
MetaTaskKineCom
)
from
numpy
import
eye
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment