42 const std::string& link)
43 : ompl::base::ProjectionEvaluator(pc->getOMPLStateSpace())
44 , planning_context_(pc)
45 , link_(planning_context_->getJointModelGroup()->getLinkModel(link))
46 , tss_(planning_context_->getCompleteInitialRobotState())
69 const Eigen::Vector3d& o = s->getGlobalLinkTransform(
link_).translation();
70 projection(0) = o.x();
71 projection(1) = o.y();
72 projection(2) = o.z();
76 const std::vector<unsigned int>& variables)
77 : ompl::base::ProjectionEvaluator(pc->getOMPLStateSpace()),
planning_context_(pc), variables_(variables)
95 for (std::size_t i = 0; i <
variables_.size(); ++i)
virtual void defaultCellSizes()
const robot_model::LinkModel * link_
virtual unsigned int getDimension() const
std::vector< double > values
virtual void project(const ompl::base::State *state, OMPLProjection projection) const
virtual void project(const ompl::base::State *state, OMPLProjection projection) const override
const ModelBasedPlanningContext * planning_context_
robot_state::RobotState * getStateStorage() const
ProjectionEvaluatorJointValue(const ModelBasedPlanningContext *pc, const std::vector< unsigned int > &variables)
virtual void defaultCellSizes()
ompl::base::EuclideanProjection & OMPLProjection
std::vector< unsigned int > variables_
ProjectionEvaluatorLinkPose(const ModelBasedPlanningContext *pc, const std::string &link)
virtual unsigned int getDimension() const
const ModelBasedStateSpacePtr & getOMPLStateSpace() const