39 #include <ompl/config.h>
40 #include <ompl/base/ProjectionEvaluator.h>
47 class ModelBasedPlanningContext;
78 std::vector<unsigned int> variables_;
A link from the robot. Contains the constant transform applied to the link and its geometry.
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
The MoveIt interface to OMPL.
Eigen::Ref< Eigen::VectorXd > OMPLProjection