Skip to content
Snippets Groups Projects
Commit a30fc7af authored by mike lautman's avatar mike lautman
Browse files

adding trajopt to list of planner_configs

parent bd3c1ef9
No related branches found
No related tags found
No related merge requests found
...@@ -20,7 +20,7 @@ planner_configs: ...@@ -20,7 +20,7 @@ planner_configs:
KPIECEkConfigDefault: KPIECEkConfigDefault:
type: geometric::KPIECE type: geometric::KPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
...@@ -44,7 +44,7 @@ planner_configs: ...@@ -44,7 +44,7 @@ planner_configs:
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
init_temperature: 10e-6 # initial temperature. default: 10e-6 init_temperature: 10e-6 # initial temperature. default: 10e-6
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
PRMkConfigDefault: PRMkConfigDefault:
...@@ -75,9 +75,9 @@ planner_configs: ...@@ -75,9 +75,9 @@ planner_configs:
STRIDEkConfigDefault: STRIDEkConfigDefault:
type: geometric::STRIDE type: geometric::STRIDE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
max_degree: 18 # max degree of a node in the GNAT. default: 12 max_degree: 18 # max degree of a node in the GNAT. default: 12
min_degree: 12 # min degree of a node in the GNAT. default: 12 min_degree: 12 # min degree of a node in the GNAT. default: 12
max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
...@@ -88,13 +88,13 @@ planner_configs: ...@@ -88,13 +88,13 @@ planner_configs:
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
init_temperature: 100 # initial temperature. default: 100 init_temperature: 100 # initial temperature. default: 100
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
LBTRRTkConfigDefault: LBTRRTkConfigDefault:
type: geometric::LBTRRT type: geometric::LBTRRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
epsilon: 0.4 # optimality approximation factor. default: 0.4 epsilon: 0.4 # optimality approximation factor. default: 0.4
BiESTkConfigDefault: BiESTkConfigDefault:
type: geometric::BiEST type: geometric::BiEST
...@@ -102,7 +102,7 @@ planner_configs: ...@@ -102,7 +102,7 @@ planner_configs:
ProjESTkConfigDefault: ProjESTkConfigDefault:
type: geometric::ProjEST type: geometric::ProjEST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
LazyPRMkConfigDefault: LazyPRMkConfigDefault:
type: geometric::LazyPRM type: geometric::LazyPRM
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
...@@ -120,6 +120,9 @@ planner_configs: ...@@ -120,6 +120,9 @@ planner_configs:
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
max_failures: 5000 # maximum consecutive failure limit. default: 5000 max_failures: 5000 # maximum consecutive failure limit. default: 5000
TrajOptDefault:
type: geometric::TrajOpt
panda_arm: panda_arm:
planner_configs: planner_configs:
- SBLkConfigDefault - SBLkConfigDefault
...@@ -145,6 +148,7 @@ panda_arm: ...@@ -145,6 +148,7 @@ panda_arm:
- LazyPRMstarkConfigDefault - LazyPRMstarkConfigDefault
- SPARSkConfigDefault - SPARSkConfigDefault
- SPARStwokConfigDefault - SPARStwokConfigDefault
- TrajOptDefault
hand: hand:
planner_configs: planner_configs:
- SBLkConfigDefault - SBLkConfigDefault
...@@ -169,4 +173,5 @@ hand: ...@@ -169,4 +173,5 @@ hand:
- LazyPRMkConfigDefault - LazyPRMkConfigDefault
- LazyPRMstarkConfigDefault - LazyPRMstarkConfigDefault
- SPARSkConfigDefault - SPARSkConfigDefault
- SPARStwokConfigDefault - SPARStwokConfigDefault
\ No newline at end of file - TrajOptDefault
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment