kinematics_service_capability.cpp
Go to the documentation of this file.
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 the 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 "kinematics_service_capability.h"
00038 #include <moveit/robot_state/conversions.h>
00039 #include <moveit/kinematic_constraints/utils.h>
00040 #include <eigen_conversions/eigen_msg.h>
00041 #include <moveit/move_group/capability_names.h>
00042 
00043 move_group::MoveGroupKinematicsService::MoveGroupKinematicsService():
00044   MoveGroupCapability("KinematicsService")
00045 {
00046 }
00047 
00048 void move_group::MoveGroupKinematicsService::initialize()
00049 {
00050   fk_service_ = root_node_handle_.advertiseService(FK_SERVICE_NAME, &MoveGroupKinematicsService::computeFKService, this);
00051   ik_service_ = root_node_handle_.advertiseService(IK_SERVICE_NAME, &MoveGroupKinematicsService::computeIKService, this);
00052 }
00053 
00054 namespace
00055 {
00056 bool isIKSolutionValid(const planning_scene::PlanningScene *planning_scene,
00057                        const kinematic_constraints::KinematicConstraintSet *constraint_set,
00058                        robot_state::JointStateGroup *group, const std::vector<double> &ik_solution)
00059 {
00060   group->setVariableValues(ik_solution);
00061   return (!planning_scene || !planning_scene->isStateColliding(*group->getRobotState(), group->getName())) &&
00062     (!constraint_set || constraint_set->decide(*group->getRobotState()).satisfied);
00063 }
00064 }
00065 
00066 void move_group::MoveGroupKinematicsService::computeIK(moveit_msgs::PositionIKRequest &req,
00067                                                        moveit_msgs::RobotState &solution,
00068                                                        moveit_msgs::MoveItErrorCodes &error_code,
00069                                                        const robot_state::StateValidityCallbackFn &constraint) const
00070 {
00071   robot_state::RobotState rs = planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
00072   robot_state::JointStateGroup *jsg = rs.getJointStateGroup(req.group_name);
00073   if (jsg)
00074   {
00075     robot_state::robotStateMsgToRobotState(req.robot_state, rs);
00076     const std::string &default_frame = context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
00077 
00078     if (req.pose_stamped_vector.empty() || req.pose_stamped_vector.size() == 1)
00079     {
00080       geometry_msgs::PoseStamped req_pose = req.pose_stamped_vector.empty() ? req.pose_stamped : req.pose_stamped_vector[0];
00081       std::string ik_link = req.pose_stamped_vector.empty() ? (req.ik_link_names.empty() ? "" : req.ik_link_names[0]) : req.ik_link_name;
00082 
00083       if (performTransform(req_pose, default_frame))
00084       {
00085         bool result_ik = false;
00086         if (ik_link.empty())
00087           result_ik = jsg->setFromIK(req_pose.pose, req.attempts, req.timeout.toSec(), constraint);
00088         else
00089           result_ik = jsg->setFromIK(req_pose.pose, ik_link, req.attempts, req.timeout.toSec(), constraint);
00090 
00091         if(result_ik)
00092         {
00093           robot_state::robotStateToRobotStateMsg(rs, solution, false);
00094           error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00095         }
00096         else
00097           error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
00098       }
00099       else
00100         error_code.val = moveit_msgs::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
00101     }
00102     else
00103     {
00104       if (req.pose_stamped_vector.size() != req.ik_link_names.size())
00105         error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME;
00106       else
00107       {
00108         bool ok = true;
00109         EigenSTL::vector_Affine3d req_poses(req.pose_stamped_vector.size());
00110         for (std::size_t k = 0 ; k < req.pose_stamped_vector.size() ; ++k)
00111         {
00112           geometry_msgs::PoseStamped msg = req.pose_stamped_vector[k];
00113           if (performTransform(msg, default_frame))
00114             tf::poseMsgToEigen(msg.pose, req_poses[k]);
00115           else
00116           {
00117             error_code.val = moveit_msgs::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
00118             ok = false;
00119             break;
00120           }
00121         }
00122         if (ok)
00123         {
00124           if (jsg->setFromIK(req_poses, req.ik_link_names, req.attempts, req.timeout.toSec(), constraint))
00125           {
00126             robot_state::robotStateToRobotStateMsg(rs, solution, false);
00127             error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00128           }
00129           else
00130             error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
00131         }
00132       }
00133     }
00134   }
00135   else
00136     error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
00137 }
00138 
00139 bool move_group::MoveGroupKinematicsService::computeIKService(moveit_msgs::GetPositionIK::Request &req, moveit_msgs::GetPositionIK::Response &res)
00140 {
00141   context_->planning_scene_monitor_->updateFrameTransforms();
00142 
00143   // check if the planning scene needs to be kept locked; if so, call computeIK() in the scope of the lock
00144   if (req.ik_request.avoid_collisions || !kinematic_constraints::isEmpty(req.ik_request.constraints))
00145   {
00146     planning_scene_monitor::LockedPlanningSceneRO ls(context_->planning_scene_monitor_);
00147     kinematic_constraints::KinematicConstraintSet kset(ls->getRobotModel());
00148     kset.add(req.ik_request.constraints, ls->getTransforms());
00149     computeIK(req.ik_request, res.solution, res.error_code, boost::bind(&isIKSolutionValid, req.ik_request.avoid_collisions ?
00150                                                                         static_cast<const planning_scene::PlanningSceneConstPtr&>(ls).get() : NULL, kset.empty() ? NULL : &kset, _1, _2));
00151   }
00152   else
00153     // compute unconstrained IK, no lock to planning scene maintained
00154     computeIK(req.ik_request, res.solution, res.error_code);
00155   return true;
00156 }
00157 
00158 bool move_group::MoveGroupKinematicsService::computeFKService(moveit_msgs::GetPositionFK::Request &req, moveit_msgs::GetPositionFK::Response &res)
00159 {
00160   if (req.fk_link_names.empty())
00161   {
00162     ROS_ERROR("No links specified for FK request");
00163     res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME;
00164     return true;
00165   }
00166 
00167   context_->planning_scene_monitor_->updateFrameTransforms();
00168 
00169   const std::string &default_frame = context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
00170   bool do_transform = !req.header.frame_id.empty() && req.header.frame_id != default_frame && context_->planning_scene_monitor_->getTFClient();
00171   bool tf_problem = false;
00172 
00173   robot_state::RobotState rs = planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
00174   robot_state::robotStateMsgToRobotState(req.robot_state, rs);
00175   for (std::size_t i = 0 ; i < req.fk_link_names.size() ; ++i)
00176     if (const robot_state::LinkState *ls = rs.getLinkState(req.fk_link_names[i]))
00177     {
00178       res.pose_stamped.resize(res.pose_stamped.size() + 1);
00179       tf::poseEigenToMsg(ls->getGlobalLinkTransform(), res.pose_stamped.back().pose);
00180       res.pose_stamped.back().header.frame_id = default_frame;
00181       res.pose_stamped.back().header.stamp = ros::Time::now();
00182       if (do_transform)
00183         if (!performTransform(res.pose_stamped.back(), req.header.frame_id))
00184           tf_problem = true;
00185       res.fk_link_names.push_back(req.fk_link_names[i]);
00186     }
00187   if (tf_problem)
00188     res.error_code.val = moveit_msgs::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
00189   else
00190     if (res.fk_link_names.size() == req.fk_link_names.size())
00191       res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00192     else
00193       res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME;
00194   return true;
00195 }
00196 
00197 #include <class_loader/class_loader.h>
00198 CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupKinematicsService, move_group::MoveGroupCapability)


move_group
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:32:44