46    const std::string& group, 
const moveit_msgs::msg::MotionPlanRequest& req,
 
   47    const moveit::core::RobotModelConstPtr& robot_model)
 const 
   60    else if (!slv.second.empty())
 
   65      for (
const auto& jt : slv.second)
 
   67        vc += jt.first->getVariableCount();
 
   68        bc += jt.second.bijection_.size();
 
   77      if ((!req.path_constraints.position_constraints.empty() ||
 
   78           !req.path_constraints.orientation_constraints.empty()) &&
 
   79          req.path_constraints.joint_constraints.empty() && req.path_constraints.visibility_constraints.empty())
 
 
int canRepresentProblem(const std::string &group, const moveit_msgs::msg::MotionPlanRequest &req, const moveit::core::RobotModelConstPtr &robot_model) const override
Decide whether the type of state space constructed by this factory could represent problems specified...