Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
M
multicontact-locomotion-planning
Manage
Activity
Members
Plan
Wiki
Code
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Analyze
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
loco-3d
multicontact-locomotion-planning
Commits
89a503ee
Commit
89a503ee
authored
6 years ago
by
Pierre Fernbach
Browse files
Options
Downloads
Patches
Plain Diff
[main,config] change way to choose the demo, use python arguments
parent
d30bd45f
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
scripts/hpp_wholebody_motion/config.py
+20
-21
20 additions, 21 deletions
scripts/hpp_wholebody_motion/config.py
with
20 additions
and
21 deletions
scripts/hpp_wholebody_motion/config.py
+
20
−
21
View file @
89a503ee
DEMO_NAME
=
"
talos_flatGround
"
DEMO_NAME
=
"
talos_obstaclesFeet
"
#DEMO_NAME = "darpa_hyq"
#DEMO_NAME = "hyq_slalom_debris"
#DEMO_NAME = "talos_table"
#DEMO_NAME="anymal_slalom_debris"
#DEMO_NAME="anymal_flatGround"
## PATHS settings :
## PATHS settings :
import
os
import
os
...
@@ -14,21 +5,16 @@ PKG_PATH = os.environ['DEVEL_HPP_DIR']+"/src/hpp-wholebody-motion"
...
@@ -14,21 +5,16 @@ PKG_PATH = os.environ['DEVEL_HPP_DIR']+"/src/hpp-wholebody-motion"
OUTPUT_DIR
=
PKG_PATH
+
"
/res
"
OUTPUT_DIR
=
PKG_PATH
+
"
/res
"
CONTACT_SEQUENCE_PATH
=
OUTPUT_DIR
+
"
/contact_sequences
"
CONTACT_SEQUENCE_PATH
=
OUTPUT_DIR
+
"
/contact_sequences
"
TIME_OPT_CONFIG_PATH
=
PKG_PATH
+
'
/timeOpt_configs
'
TIME_OPT_CONFIG_PATH
=
PKG_PATH
+
'
/timeOpt_configs
'
LOAD_CS
=
False
LOAD_CS_COM
=
False
SAVE_CS
=
True
SAVE_CS_COM
=
True
EXPORT_GAZEBO
=
True
LOAD_CS
=
True
LOAD_CS
=
True
LOAD_CS_COM
=
True
LOAD_CS_COM
=
True
SAVE_CS
=
False
SAVE_CS
=
not
LOAD_CS
and
True
SAVE_CS_COM
=
Fals
e
SAVE_CS_COM
=
not
LOAD_CS_COM
and
Tru
e
EXPORT_GAZEBO
=
Fals
e
EXPORT_GAZEBO
=
Tru
e
EXPORT_PATH
=
OUTPUT_DIR
+
"
/export
"
EXPORT_PATH
=
OUTPUT_DIR
+
"
/export
"
##DISPLAY settings :
##DISPLAY settings :
DISPLAY_CS
=
False
# display contact sequence from rbprm
DISPLAY_CS
=
False
# display contact sequence from rbprm
DISPLAY_CS_STONES
=
Fals
e
# display stepping stones
DISPLAY_CS_STONES
=
Tru
e
# display stepping stones
DISPLAY_INIT_GUESS_TRAJ
=
False
DISPLAY_INIT_GUESS_TRAJ
=
False
DISPLAY_WP_COST
=
False
DISPLAY_WP_COST
=
False
DISPLAY_COM_TRAJ
=
True
DISPLAY_COM_TRAJ
=
True
...
@@ -55,16 +41,29 @@ EFF_CHECK_COLLISION = True
...
@@ -55,16 +41,29 @@ EFF_CHECK_COLLISION = True
## Settings for whole body :
## Settings for whole body :
YAW_ROT_GAIN
=
1.
YAW_ROT_GAIN
=
1.
USE_CROC_COM
=
False
USE_CROC_COM
=
False
WB_VERBOSE
=
Tru
e
WB_VERBOSE
=
Fals
e
WB_STOP_AT_EACH_PHASE
=
Tru
e
WB_STOP_AT_EACH_PHASE
=
Fals
e
IK_dt
=
0.001
# controler time step
IK_dt
=
0.001
# controler time step
IK_PRINT_N
=
500
# print state of the problem every IK_PRINT_N time steps (if verbose = True)
IK_PRINT_N
=
500
# print state of the problem every IK_PRINT_N time steps (if verbose = True)
# import specific settings for the selected demo. This settings may override default ones.
# import specific settings for the selected demo. This settings may override default ones.
import
importlib
import
importlib
import
sys
if
len
(
sys
.
argv
)
<
2
:
raise
IOError
(
"
You must call this script with the name of the config file (one of the file contained in hpp_wholebody_motion.demo_config)
"
)
import
argparse
parser
=
argparse
.
ArgumentParser
(
description
=
"
todo
"
)
parser
.
add_argument
(
'
demo_name
'
,
type
=
str
,
help
=
"
The name of the demo configuration file to load
"
)
args
=
parser
.
parse_args
()
DEMO_NAME
=
args
.
demo_name
print
"
# Load demo config :
"
,
DEMO_NAME
# Import the module
# Import the module
demo_cfg
=
importlib
.
import_module
(
'
hpp_wholebody_motion.demo_configs.
'
+
DEMO_NAME
)
try
:
demo_cfg
=
importlib
.
import_module
(
'
hpp_wholebody_motion.demo_configs.
'
+
DEMO_NAME
)
except
ImportError
:
raise
NameError
(
"
No demo config file with the given name in hpp_wholebody_motion.demo_config
"
)
# Determine a list of names to copy to the current name space
# Determine a list of names to copy to the current name space
names
=
getattr
(
demo_cfg
,
'
__all__
'
,
[
n
for
n
in
dir
(
demo_cfg
)
if
not
n
.
startswith
(
'
_
'
)])
names
=
getattr
(
demo_cfg
,
'
__all__
'
,
[
n
for
n
in
dir
(
demo_cfg
)
if
not
n
.
startswith
(
'
_
'
)])
# Copy those names into the current name space
# Copy those names into the current name space
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment