ikfast_moveit_state_adapter.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Apache License)
00003  *
00004  * Copyright (c) 2016, Jonathan Meyer
00005  *
00006  * Licensed under the Apache License, Version 2.0 (the "License");
00007  * you may not use this file except in compliance with the License.
00008  * You may obtain a copy of the License at
00009  *
00010  * http://www.apache.org/licenses/LICENSE-2.0
00011  *
00012  * Unless required by applicable law or agreed to in writing, software
00013  * distributed under the License is distributed on an "AS IS" BASIS,
00014  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015  * See the License for the specific language governing permissions and
00016  * limitations under the License.
00017  */
00018 
00019 #include "descartes_moveit/ikfast_moveit_state_adapter.h"
00020 
00021 #include <eigen_conversions/eigen_msg.h>
00022 #include <ros/node_handle.h>
00023 
00024 const static std::string default_base_frame = "base_link";
00025 const static std::string default_tool_frame = "tool0";
00026 
00027 // Compute the 'joint distance' between two poses
00028 static double distance(const std::vector<double>& a, const std::vector<double>& b)
00029 {
00030   double cost = 0.0;
00031   for (size_t i = 0; i < a.size(); ++i)
00032     cost += std::abs(b[i] - a[i]);
00033   return cost;
00034 }
00035 
00036 // Compute the index of the closest joint pose in 'candidates' from 'target'
00037 static size_t closestJointPose(const std::vector<double>& target, const std::vector<std::vector<double>>& candidates)
00038 {
00039   size_t closest = 0;  // index into candidates
00040   double lowest_cost = std::numeric_limits<double>::max();
00041   for (size_t i = 0; i < candidates.size(); ++i)
00042   {
00043     assert(target.size() == candidates[i].size());
00044     double c = distance(target, candidates[i]);
00045     if (c < lowest_cost)
00046     {
00047       closest = i;
00048       lowest_cost = c;
00049     }
00050   }
00051   return closest;
00052 }
00053 
00054 bool descartes_moveit::IkFastMoveitStateAdapter::initialize(const std::string& robot_description,
00055                                                             const std::string& group_name,
00056                                                             const std::string& world_frame,
00057                                                             const std::string& tcp_frame)
00058 {
00059   if (!MoveitStateAdapter::initialize(robot_description, group_name, world_frame, tcp_frame))
00060   {
00061     return false;
00062   }
00063 
00064   return computeIKFastTransforms();
00065 }
00066 
00067 bool descartes_moveit::IkFastMoveitStateAdapter::getAllIK(const Eigen::Affine3d& pose,
00068                                                           std::vector<std::vector<double>>& joint_poses) const
00069 {
00070   joint_poses.clear();
00071   const auto& solver = joint_group_->getSolverInstance();
00072 
00073   // Transform input pose
00074   Eigen::Affine3d tool_pose = world_to_base_.frame_inv * pose * tool0_to_tip_.frame;
00075 
00076   // convert to geometry_msgs ...
00077   geometry_msgs::Pose geometry_pose;
00078   tf::poseEigenToMsg(tool_pose, geometry_pose);
00079   std::vector<geometry_msgs::Pose> poses = { geometry_pose };
00080 
00081   std::vector<double> dummy_seed(getDOF(), 0.0);
00082   std::vector<std::vector<double>> joint_results;
00083   kinematics::KinematicsResult result;
00084   kinematics::KinematicsQueryOptions options;  // defaults are reasonable as of Indigo
00085 
00086   if (!solver->getPositionIK(poses, dummy_seed, joint_results, result, options))
00087   {
00088     return false;
00089   }
00090 
00091   for (auto& sol : joint_results)
00092   {
00093     if (isValid(sol))
00094       joint_poses.push_back(std::move(sol));
00095   }
00096 
00097   return joint_poses.size() > 0;
00098 }
00099 
00100 bool descartes_moveit::IkFastMoveitStateAdapter::getIK(const Eigen::Affine3d& pose,
00101                                                        const std::vector<double>& seed_state,
00102                                                        std::vector<double>& joint_pose) const
00103 {
00104   // Descartes Robot Model interface calls for 'closest' point to seed position
00105   std::vector<std::vector<double>> joint_poses;
00106   if (!getAllIK(pose, joint_poses))
00107     return false;
00108   // Find closest joint pose; getAllIK() does isValid checks already
00109   joint_pose = joint_poses[closestJointPose(seed_state, joint_poses)];
00110   return true;
00111 }
00112 
00113 bool descartes_moveit::IkFastMoveitStateAdapter::getFK(const std::vector<double>& joint_pose,
00114                                                        Eigen::Affine3d& pose) const
00115 {
00116   const auto& solver = joint_group_->getSolverInstance();
00117 
00118   std::vector<std::string> tip_frame = { solver->getTipFrame() };
00119   std::vector<geometry_msgs::Pose> output;
00120 
00121   if (!isValid(joint_pose))
00122     return false;
00123 
00124   if (!solver->getPositionFK(tip_frame, joint_pose, output))
00125     return false;
00126 
00127   tf::poseMsgToEigen(output[0], pose);  // pose in frame of IkFast base
00128   pose = world_to_base_.frame * pose * tool0_to_tip_.frame_inv;
00129   return true;
00130 }
00131 
00132 void descartes_moveit::IkFastMoveitStateAdapter::setState(const moveit::core::RobotState& state)
00133 {
00134   descartes_moveit::MoveitStateAdapter::setState(state);
00135   computeIKFastTransforms();
00136 }
00137 
00138 bool descartes_moveit::IkFastMoveitStateAdapter::computeIKFastTransforms()
00139 {
00140   // look up the IKFast base and tool frame
00141   ros::NodeHandle nh;
00142   std::string ikfast_base_frame, ikfast_tool_frame;
00143   nh.param<std::string>("ikfast_base_frame", ikfast_base_frame, default_base_frame);
00144   nh.param<std::string>("ikfast_tool_frame", ikfast_tool_frame, default_tool_frame);
00145 
00146   if (!robot_state_->knowsFrameTransform(ikfast_base_frame))
00147   {
00148     logError("IkFastMoveitStateAdapter: Cannot find transformation to frame '%s' in group '%s'.",
00149              ikfast_base_frame.c_str(), group_name_.c_str());
00150     return false;
00151   }
00152 
00153   if (!robot_state_->knowsFrameTransform(ikfast_tool_frame))
00154   {
00155     logError("IkFastMoveitStateAdapter: Cannot find transformation to frame '%s' in group '%s'.",
00156              ikfast_tool_frame.c_str(), group_name_.c_str());
00157     return false;
00158   }
00159 
00160   // calculate frames
00161   tool0_to_tip_ = descartes_core::Frame(robot_state_->getFrameTransform(tool_frame_).inverse() *
00162                                         robot_state_->getFrameTransform(ikfast_tool_frame));
00163 
00164   world_to_base_ = descartes_core::Frame(world_to_root_.frame * robot_state_->getFrameTransform(ikfast_base_frame));
00165 
00166   logInform("IkFastMoveitStateAdapter: initialized with IKFast tool frame '%s' and base frame '%s'.",
00167             ikfast_tool_frame.c_str(), ikfast_base_frame.c_str());
00168   return true;
00169 }


descartes_moveit
Author(s): Shaun Edwards
autogenerated on Thu Jun 6 2019 21:36:08