44 const std::string& link)
45 : ompl::base::ProjectionEvaluator(pc->getOMPLStateSpace())
46 , planning_context_(pc)
47 , link_(planning_context_->getJointModelGroup()->getLinkModel(link))
48 , tss_(planning_context_->getCompleteInitialRobotState())
69 planning_context_->getOMPLStateSpace()->copyToRobotState(*
s, state);
71 const Eigen::Vector3d& o =
s->getGlobalLinkTransform(link_).translation();
72 projection(0) = o.x();
73 projection(1) = o.y();
74 projection(2) = o.z();
78 std::vector<unsigned int> variables)
79 : ompl::base::ProjectionEvaluator(pc->getOMPLStateSpace()), variables_(
std::move(variables))
85 return variables_.size();
91 cellSizes_.resize(variables_.size(), 0.1);
97 for (std::size_t i = 0; i < variables_.size(); ++i)