From 0ad4d5ee3b9276d4eb6f70a0a9ab86af0a90de01 Mon Sep 17 00:00:00 2001 From: Stephanie Eng Date: Mon, 28 Nov 2022 08:40:06 -0500 Subject: [PATCH] Use PRM instead of RRTConnect --- .../constrained_planning_state_space_factory.cpp | 6 +++--- .../ompl_interface/test/test_planning_context_manager.cpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space_factory.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space_factory.cpp index 20a1acf3d7..7830f81c37 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space_factory.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space_factory.cpp @@ -45,9 +45,9 @@ ConstrainedPlanningStateSpaceFactory::ConstrainedPlanningStateSpaceFactory() : M type_ = ConstrainedPlanningStateSpace::PARAMETERIZATION_TYPE; } -int ConstrainedPlanningStateSpaceFactory::canRepresentProblem(const std::string& group, - const moveit_msgs::msg::MotionPlanRequest& req, - const moveit::core::RobotModelConstPtr& robot_model) const +int ConstrainedPlanningStateSpaceFactory::canRepresentProblem( + const std::string& /*group*/, const moveit_msgs::msg::MotionPlanRequest& req, + const moveit::core::RobotModelConstPtr& /*robot_model*/) const { // If we have exactly one position or orientation constraint, prefer the constrained planning state space auto num_constraints = diff --git a/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp b/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp index e14ce9389b..463ad475c7 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp @@ -123,7 +123,7 @@ class TestPlanningContext : public ompl_interface_testing::LoadTestRobot, public pconfig_settings.name = group_name_; pconfig_settings.config = { { "enforce_joint_model_state_space", "0" }, { "projection_evaluator", "joints(" + joint_names[0] + "," + joint_names[1] + ")" }, - { "type", "geometric::RRTConnect" } }; + { "type", "geometric::PRM" } }; planning_interface::PlannerConfigurationMap pconfig_map{ { pconfig_settings.name, pconfig_settings } }; moveit_msgs::msg::MoveItErrorCodes error_code;