00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2012, 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/parameterization/work_space/pose_model_state_space_factory.h> 00038 #include <moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h> 00039 00040 ompl_interface::PoseModelStateSpaceFactory::PoseModelStateSpaceFactory() : ModelBasedStateSpaceFactory() 00041 { 00042 type_ = PoseModelStateSpace::PARAMETERIZATION_TYPE; 00043 } 00044 00045 int ompl_interface::PoseModelStateSpaceFactory::canRepresentProblem(const std::string& group, 00046 const moveit_msgs::MotionPlanRequest& req, 00047 const robot_model::RobotModelConstPtr& kmodel) const 00048 { 00049 const robot_model::JointModelGroup* jmg = kmodel->getJointModelGroup(group); 00050 if (jmg) 00051 { 00052 const std::pair<robot_model::JointModelGroup::KinematicsSolver, robot_model::JointModelGroup::KinematicsSolverMap>& 00053 slv = jmg->getGroupKinematics(); 00054 bool ik = false; 00055 // check that we have a direct means to compute IK 00056 if (slv.first) 00057 ik = jmg->getVariableCount() == slv.first.bijection_.size(); 00058 else if (!slv.second.empty()) 00059 { 00060 // or an IK solver for each of the subgroups 00061 unsigned int vc = 0; 00062 unsigned int bc = 0; 00063 for (robot_model::JointModelGroup::KinematicsSolverMap::const_iterator jt = slv.second.begin(); 00064 jt != slv.second.end(); ++jt) 00065 { 00066 vc += jt->first->getVariableCount(); 00067 bc += jt->second.bijection_.size(); 00068 } 00069 if (vc == jmg->getVariableCount() && vc == bc) 00070 ik = true; 00071 } 00072 00073 if (ik) 00074 { 00075 // if we have path constraints, we prefer interpolating in pose space 00076 if ((!req.path_constraints.position_constraints.empty() || 00077 !req.path_constraints.orientation_constraints.empty()) && 00078 req.path_constraints.joint_constraints.empty() && req.path_constraints.visibility_constraints.empty()) 00079 return 150; 00080 else 00081 return 50; 00082 } 00083 } 00084 return -1; 00085 } 00086 00087 ompl_interface::ModelBasedStateSpacePtr 00088 ompl_interface::PoseModelStateSpaceFactory::allocStateSpace(const ModelBasedStateSpaceSpecification& space_spec) const 00089 { 00090 return ModelBasedStateSpacePtr(new PoseModelStateSpace(space_spec)); 00091 }