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);
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)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
void project(const ompl::base::State *state, OMPLProjection projection) const override
unsigned int getDimension() const override
void defaultCellSizes() override
ProjectionEvaluatorJointValue(const ModelBasedPlanningContext *pc, std::vector< unsigned int > variables)
unsigned int getDimension() const override
ProjectionEvaluatorLinkPose(const ModelBasedPlanningContext *pc, const std::string &link)
void project(const ompl::base::State *state, OMPLProjection projection) const override
void defaultCellSizes() override
Eigen::Ref< Eigen::VectorXd > OMPLProjection