You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
# Based on Kinova's parameters: https://github.com/Kinovarobotics/kinova-ros/blob/noetic-devel/kinova_moveit/robot_configs/j2n6s300_moveit_config/config/ompl_planning.yaml
13
13
planner_configs:
14
+
AnytimePathShortening:
15
+
type: geometric::AnytimePathShortening
16
+
shortcut: 1# Attempt to shortcut all new solution paths
max_hybrid_paths: 8# Number of hybrid paths generated per iteration
19
+
num_planners: 4# The number of default planners to use for planning
20
+
planners: "RRTConnect[intermediate_states=0 range=0.05]"# A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
14
21
SBLkConfigDefault:
15
22
type: geometric::SBL
16
23
range: 0.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
@@ -42,10 +49,11 @@ planner_configs:
42
49
goal_bias: 0.05# When close to goal select goal, with this probability? default: 0.05
43
50
RRTConnectkConfigDefault:
44
51
type: geometric::RRTConnect
45
-
range: 0.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
52
+
intermediate_states: 0# Whether to add intermediate states to the plan, default 0
53
+
range: 0.05# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
46
54
RRTstarkConfigDefault:
47
55
type: geometric::RRTstar
48
-
range: 3.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() (in practice, for ADA, this default is ~7)
56
+
range: 100.0#3.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() (in practice, for ADA, this default is ~7, around 20% of the maximum extent of the space)
49
57
goal_bias: 0.05# When close to goal select goal, with this probability? default: 0.05
50
58
delay_collision_checking: 1# Stop collision checking as soon as C-free parent found. default 1
0 commit comments