Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/ompl_interface/detail/projection_evaluators.h>
00038 #include <moveit/ompl_interface/model_based_planning_context.h>
00039
00040 ompl_interface::ProjectionEvaluatorLinkPose::ProjectionEvaluatorLinkPose(const ModelBasedPlanningContext *pc, const std::string &link) :
00041 ompl::base::ProjectionEvaluator(pc->getOMPLStateSpace()), planning_context_(pc),
00042 group_name_(planning_context_->getGroupName()), link_name_(link),
00043 tss_(planning_context_->getCompleteInitialRobotState())
00044 {
00045 }
00046
00047 unsigned int ompl_interface::ProjectionEvaluatorLinkPose::getDimension() const
00048 {
00049 return 3;
00050 }
00051
00052 void ompl_interface::ProjectionEvaluatorLinkPose::defaultCellSizes()
00053 {
00054 cellSizes_.resize(3);
00055 cellSizes_[0] = 0.1;
00056 cellSizes_[1] = 0.1;
00057 cellSizes_[2] = 0.1;
00058 }
00059
00060 void ompl_interface::ProjectionEvaluatorLinkPose::project(const ompl::base::State *state, ompl::base::EuclideanProjection &projection) const
00061 {
00062 robot_state::RobotState *s = tss_.getStateStorage();
00063 planning_context_->getOMPLStateSpace()->copyToRobotState(*s, state);
00064
00065 const robot_state::LinkState *ls = s->getLinkState(link_name_);
00066 const Eigen::Vector3d &o = ls->getGlobalLinkTransform().translation();
00067 projection(0) = o.x();
00068 projection(1) = o.y();
00069 projection(2) = o.z();
00070 }
00071
00072 ompl_interface::ProjectionEvaluatorJointValue::ProjectionEvaluatorJointValue(const ModelBasedPlanningContext *pc,
00073 const std::vector<std::pair<std::string, unsigned int> > &joints) :
00074 ompl::base::ProjectionEvaluator(pc->getOMPLStateSpace()), planning_context_(pc), joints_(joints)
00075 {
00076 dimension_ = 0;
00077 for (std::size_t i = 0 ; i < joints_.size() ; ++i)
00078 dimension_ += joints_[i].second;
00079 }
00080
00081 unsigned int ompl_interface::ProjectionEvaluatorJointValue::getDimension() const
00082 {
00083 return dimension_;
00084 }
00085
00086 void ompl_interface::ProjectionEvaluatorJointValue::defaultCellSizes()
00087 {
00088 cellSizes_.clear();
00089 cellSizes_.resize(dimension_, 0.1);
00090 }
00091
00092 void ompl_interface::ProjectionEvaluatorJointValue::project(const ompl::base::State *state, ompl::base::EuclideanProjection &projection) const
00093 {
00094 unsigned int k = 0;
00095 for (std::size_t i = 0 ; i < joints_.size() ; ++i)
00096 {
00097 const double *v = planning_context_->getOMPLStateSpace()->getValueAddressAtName(state, joints_[i].first);
00098 for (unsigned int j = 0 ; j < joints_[i].second ; ++j)
00099 projection(k++) = v[j];
00100 }
00101 }