Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add AnytimePathShortening to ada_moveit #50

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 12 additions & 3 deletions ada_moveit/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,15 @@ request_adapters: >-
default_planner_request_adapters/FixWorkspaceBounds
# 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
planner_configs:
# NOTE: In practice, MoveIt2 hybridizes and shortcuts by default:
# https://github.com/moveit/moveit2/blob/e7872ebf92146bb80930ec98cf6c181e8384e99c/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp#L81
AnytimePathShortening:
type: geometric::AnytimePathShortening
shortcut: 1 # Attempt to shortcut all new solution paths
hybridize: 1 # Compute hybrid solution trajectories
max_hybrid_paths: 8 # Number of hybrid paths generated per iteration
num_planners: 4 # The number of default planners to use for planning
planners: "RRTConnect[range=0.01]" # 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]"
SBLkConfigDefault:
type: geometric::SBL
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
Expand Down Expand Up @@ -39,7 +48,8 @@ planner_configs:
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
RRTConnectkConfigDefault:
type: geometric::RRTConnect
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
intermediate_states: 0 # Whether to add intermediate states to the plan, default 0
range: 0.01 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
RRTstarkConfigDefault:
type: geometric::RRTstar
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)
Expand All @@ -65,6 +75,7 @@ jaco_arm:
enforce_constrained_state_space: true
projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2)
planner_configs:
- AnytimePathShortening
- SBLkConfigDefault
- ESTkConfigDefault
- LBKPIECEkConfigDefault
Expand All @@ -77,8 +88,6 @@ jaco_arm:
- PRMkConfigDefault
- PRMstarkConfigDefault
hand:
enforce_constrained_state_space: true
projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2)
planner_configs:
- SBLkConfigDefault
- ESTkConfigDefault
Expand Down
4 changes: 3 additions & 1 deletion ada_moveit/launch/demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,9 @@ def generate_launch_description():
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
arguments=["--ros-args", "--log-level", log_level],
# Commented out the log-level since the joint state publisher logs every joint read
# when on debug level
arguments=["--ros-args"],#, "--log-level", log_level],
)
)

Expand Down