Skip to content

Commit 616a9c5

Browse files
authored
Add AnytimePathShortening to ada_moveit (#50)
* Add Anytime Path Shortening * Tune parameters * Run pre-commit * Switch to RRT*-Inf
1 parent 37bf7ce commit 616a9c5

File tree

2 files changed

+14
-5
lines changed

2 files changed

+14
-5
lines changed

ada_moveit/config/ompl_planning.yaml

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,13 @@ request_adapters: >-
1111
default_planner_request_adapters/FixWorkspaceBounds
1212
# 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
1313
planner_configs:
14+
AnytimePathShortening:
15+
type: geometric::AnytimePathShortening
16+
shortcut: 1 # Attempt to shortcut all new solution paths
17+
hybridize: 1 # Compute hybrid solution trajectories
18+
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]"
1421
SBLkConfigDefault:
1522
type: geometric::SBL
1623
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
@@ -42,10 +49,11 @@ planner_configs:
4249
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
4350
RRTConnectkConfigDefault:
4451
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()
4654
RRTstarkConfigDefault:
4755
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)
4957
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
5058
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
5159
TRRTkConfigDefault:
@@ -68,6 +76,7 @@ jaco_arm:
6876
enforce_constrained_state_space: true
6977
projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2)
7078
planner_configs:
79+
- AnytimePathShortening
7180
- SBLkConfigDefault
7281
- ESTkConfigDefault
7382
- LBKPIECEkConfigDefault
@@ -80,8 +89,6 @@ jaco_arm:
8089
- PRMkConfigDefault
8190
- PRMstarkConfigDefault
8291
hand:
83-
enforce_constrained_state_space: true
84-
projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2)
8592
planner_configs:
8693
- SBLkConfigDefault
8794
- ESTkConfigDefault

ada_moveit/launch/demo.launch.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -261,7 +261,9 @@ def generate_launch_description():
261261
package="controller_manager",
262262
executable="ros2_control_node",
263263
parameters=[robot_description, robot_controllers],
264-
arguments=["--ros-args", "--log-level", log_level],
264+
# Commented out the log-level since the joint state publisher logs every joint read
265+
# when on debug level
266+
arguments=["--ros-args"], # , "--log-level", log_level],
265267
)
266268
)
267269

0 commit comments

Comments
 (0)