From 0ed395995d35040b6654c815c9ee33789059bd41 Mon Sep 17 00:00:00 2001 From: Dewey Date: Wed, 12 May 2021 11:02:15 -0700 Subject: [PATCH 1/2] update enforce_joint_model_state_space in config --- fetch_moveit_config/config/ompl_planning.yaml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/fetch_moveit_config/config/ompl_planning.yaml b/fetch_moveit_config/config/ompl_planning.yaml index 6910e9f8..dc01080e 100644 --- a/fetch_moveit_config/config/ompl_planning.yaml +++ b/fetch_moveit_config/config/ompl_planning.yaml @@ -36,6 +36,10 @@ arm: - PRMstarkConfigDefault projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) longest_valid_segment_fraction: 0.005 + # this will enforce JointModelStateSpaceFactory for problem representing see + # https://github.com/ros-planning/moveit/pull/541 for detail + # basically this would allow path constraints in moveit_commander to work properly + enforce_joint_model_state_space: true arm_with_torso: planner_configs: - SBLkConfigDefault @@ -51,6 +55,10 @@ arm_with_torso: - PRMstarkConfigDefault projection_evaluator: joints(torso_lift_joint,shoulder_pan_joint) longest_valid_segment_fraction: 0.05 + # this will enforce JointModelStateSpaceFactory for problem representing see + # https://github.com/ros-planning/moveit/pull/541 for detail + # basically this would allow path constraints in moveit_commander to work properly + enforce_joint_model_state_space: true gripper: planner_configs: - SBLkConfigDefault From ecf80163f0bad703ef763bb6a8a6ff9f0fa32607 Mon Sep 17 00:00:00 2001 From: Dewey Date: Thu, 13 May 2021 15:43:41 -0700 Subject: [PATCH 2/2] update ompl_planning with enforce joint model state space set to true This will enforce JointModelStateSpaceFactory for problem representing see https://github.com/ros-planning/moveit/pull/541 for detail basically this would allow path constraints in moveit_commander to work properly --- fetch_moveit_config/config/ompl_planning.yaml | 6 ------ 1 file changed, 6 deletions(-) diff --git a/fetch_moveit_config/config/ompl_planning.yaml b/fetch_moveit_config/config/ompl_planning.yaml index dc01080e..9af2709c 100644 --- a/fetch_moveit_config/config/ompl_planning.yaml +++ b/fetch_moveit_config/config/ompl_planning.yaml @@ -36,9 +36,6 @@ arm: - PRMstarkConfigDefault projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) longest_valid_segment_fraction: 0.005 - # this will enforce JointModelStateSpaceFactory for problem representing see - # https://github.com/ros-planning/moveit/pull/541 for detail - # basically this would allow path constraints in moveit_commander to work properly enforce_joint_model_state_space: true arm_with_torso: planner_configs: @@ -55,9 +52,6 @@ arm_with_torso: - PRMstarkConfigDefault projection_evaluator: joints(torso_lift_joint,shoulder_pan_joint) longest_valid_segment_fraction: 0.05 - # this will enforce JointModelStateSpaceFactory for problem representing see - # https://github.com/ros-planning/moveit/pull/541 for detail - # basically this would allow path constraints in moveit_commander to work properly enforce_joint_model_state_space: true gripper: planner_configs: