projection_evaluators.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/ompl_interface/detail/projection_evaluators.h>
00038 #include <moveit/ompl_interface/model_based_planning_context.h>
00039 #include <moveit/ompl_interface/parameterization/model_based_state_space.h>
00040 
00041 ompl_interface::ProjectionEvaluatorLinkPose::ProjectionEvaluatorLinkPose(const ModelBasedPlanningContext* pc,
00042                                                                          const std::string& link)
00043   : ompl::base::ProjectionEvaluator(pc->getOMPLStateSpace())
00044   , planning_context_(pc)
00045   , link_(planning_context_->getJointModelGroup()->getLinkModel(link))
00046   , tss_(planning_context_->getCompleteInitialRobotState())
00047 {
00048 }
00049 
00050 unsigned int ompl_interface::ProjectionEvaluatorLinkPose::getDimension() const
00051 {
00052   return 3;
00053 }
00054 
00055 void ompl_interface::ProjectionEvaluatorLinkPose::defaultCellSizes()
00056 {
00057   cellSizes_.resize(3);
00058   cellSizes_[0] = 0.1;
00059   cellSizes_[1] = 0.1;
00060   cellSizes_[2] = 0.1;
00061 }
00062 
00063 void ompl_interface::ProjectionEvaluatorLinkPose::project(const ompl::base::State* state,
00064                                                           ompl::base::EuclideanProjection& projection) const
00065 {
00066   robot_state::RobotState* s = tss_.getStateStorage();
00067   planning_context_->getOMPLStateSpace()->copyToRobotState(*s, state);
00068 
00069   const Eigen::Vector3d& o = s->getGlobalLinkTransform(link_).translation();
00070   projection(0) = o.x();
00071   projection(1) = o.y();
00072   projection(2) = o.z();
00073 }
00074 
00075 ompl_interface::ProjectionEvaluatorJointValue::ProjectionEvaluatorJointValue(const ModelBasedPlanningContext* pc,
00076                                                                              const std::vector<unsigned int>& variables)
00077   : ompl::base::ProjectionEvaluator(pc->getOMPLStateSpace()), planning_context_(pc), variables_(variables)
00078 {
00079 }
00080 
00081 unsigned int ompl_interface::ProjectionEvaluatorJointValue::getDimension() const
00082 {
00083   return variables_.size();
00084 }
00085 
00086 void ompl_interface::ProjectionEvaluatorJointValue::defaultCellSizes()
00087 {
00088   cellSizes_.clear();
00089   cellSizes_.resize(variables_.size(), 0.1);
00090 }
00091 
00092 void ompl_interface::ProjectionEvaluatorJointValue::project(const ompl::base::State* state,
00093                                                             ompl::base::EuclideanProjection& projection) const
00094 {
00095   for (std::size_t i = 0; i < variables_.size(); ++i)
00096     projection(i) = state->as<ModelBasedStateSpace::StateType>()->values[variables_[i]];
00097 }


ompl
Author(s): Ioan Sucan
autogenerated on Mon Jul 24 2017 02:21:33