From 950a83b0267ff4442f86005762b0123b6f9ccdc7 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Wed, 13 Nov 2024 19:12:32 -0800 Subject: [PATCH 1/3] Add Anytime Path Shortening --- ada_moveit/config/ompl_planning.yaml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ada_moveit/config/ompl_planning.yaml b/ada_moveit/config/ompl_planning.yaml index 7072746..2053beb 100644 --- a/ada_moveit/config/ompl_planning.yaml +++ b/ada_moveit/config/ompl_planning.yaml @@ -11,6 +11,13 @@ 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: + AnytimePathShortening: + type: geometric::AnytimePathShortening + shortcut: 1 # Attempt to shortcut all new solution paths + hybridize: 1 # Compute hybrid solution trajectories + max_hybrid_paths: 24 # Number of hybrid paths generated per iteration + num_planners: 4 # The number of default planners to use for planning + planners: "RRTConnect" # 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() @@ -68,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 From a2cd3e09c21fb27d20739bdc902a8affd3830901 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Mon, 2 Dec 2024 13:17:51 -0800 Subject: [PATCH 2/3] Tune parameters --- ada_moveit/config/ompl_planning.yaml | 9 ++++----- ada_moveit/launch/demo.launch.py | 4 +++- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/ada_moveit/config/ompl_planning.yaml b/ada_moveit/config/ompl_planning.yaml index 2053beb..62779d4 100644 --- a/ada_moveit/config/ompl_planning.yaml +++ b/ada_moveit/config/ompl_planning.yaml @@ -15,9 +15,9 @@ planner_configs: type: geometric::AnytimePathShortening shortcut: 1 # Attempt to shortcut all new solution paths hybridize: 1 # Compute hybrid solution trajectories - max_hybrid_paths: 24 # Number of hybrid paths generated per iteration + 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" # 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]" + 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]" SBLkConfigDefault: type: geometric::SBL range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() @@ -49,7 +49,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.05 # 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) @@ -88,8 +89,6 @@ jaco_arm: - PRMkConfigDefault - PRMstarkConfigDefault hand: - enforce_constrained_state_space: true - projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2) planner_configs: - SBLkConfigDefault - ESTkConfigDefault diff --git a/ada_moveit/launch/demo.launch.py b/ada_moveit/launch/demo.launch.py index 4dbf678..d5e790a 100644 --- a/ada_moveit/launch/demo.launch.py +++ b/ada_moveit/launch/demo.launch.py @@ -261,7 +261,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], ) ) From c36c20c9363ba796e98878cd5b4259a14db70184 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Mon, 16 Dec 2024 15:04:43 -0800 Subject: [PATCH 3/3] Run pre-commit --- ada_moveit/launch/demo.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ada_moveit/launch/demo.launch.py b/ada_moveit/launch/demo.launch.py index d5e790a..692b324 100644 --- a/ada_moveit/launch/demo.launch.py +++ b/ada_moveit/launch/demo.launch.py @@ -263,7 +263,7 @@ def generate_launch_description(): parameters=[robot_description, robot_controllers], # 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], + arguments=["--ros-args"], # , "--log-level", log_level], ) )