Skip to content

Commit

Permalink
Use PRM instead of RRTConnect
Browse files Browse the repository at this point in the history
  • Loading branch information
stephanie-eng committed Nov 28, 2022
1 parent 7e00e14 commit 0ad4d5e
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
Expand Up @@ -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 =
Expand Down
Expand Up @@ -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;
Expand Down

0 comments on commit 0ad4d5e

Please sign in to comment.