diff --git a/ada_moveit/config/ompl_planning.yaml b/ada_moveit/config/ompl_planning.yaml index f4cc886..e402927 100644 --- a/ada_moveit/config/ompl_planning.yaml +++ b/ada_moveit/config/ompl_planning.yaml @@ -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() @@ -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) @@ -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 @@ -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 diff --git a/ada_moveit/launch/demo.launch.py b/ada_moveit/launch/demo.launch.py index c0793b2..97608b6 100644 --- a/ada_moveit/launch/demo.launch.py +++ b/ada_moveit/launch/demo.launch.py @@ -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], ) )