47     const moveit::core::RobotModelConstPtr& robot_model)
 const 
   58     else if (!slv.second.empty())
 
   63       for (
const auto& jt : slv.second)
 
   65         vc += jt.first->getVariableCount();
 
   66         bc += jt.second.bijection_.size();
 
   75       if ((!req.path_constraints.position_constraints.empty() ||
 
   76            !req.path_constraints.orientation_constraints.empty()) &&
 
   77           req.path_constraints.joint_constraints.empty() && req.path_constraints.visibility_constraints.empty())
 
   86 ompl_interface::ModelBasedStateSpacePtr
 
   89   return std::make_shared<PoseModelStateSpace>(space_spec);
 
const std::pair< KinematicsSolver, KinematicsSolverMap > & getGroupKinematics() const
 
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
 
std::map< const JointModelGroup *, KinematicsSolver > KinematicsSolverMap
Map from group instances to allocator functions & bijections.
 
PoseModelStateSpaceFactory()
 
ModelBasedStateSpacePtr allocStateSpace(const ModelBasedStateSpaceSpecification &space_spec) const override
 
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...
 
static const std::string PARAMETERIZATION_TYPE
 
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest